Skip to content

Commit

Permalink
feat(autoware_obstacle_cruise_planner)!: tier4_debug_msgs changed to …
Browse files Browse the repository at this point in the history
…autoware_internal_debug_msgs in autoware_obstacle_cruise_planner (#9905)

feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_obstacle_cruise_planner

Signed-off-by: vish0012 <[email protected]>
  • Loading branch information
vish0012 authored Jan 21, 2025
1 parent 79f9ecc commit b3c3f7a
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@

#include <rclcpp/rclcpp.hpp>

#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp"

#include <array>

using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;

class CruisePlanningDebugInfo
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@

#include <rclcpp/rclcpp.hpp>

#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp"

#include <array>

using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;

class StopPlanningDebugInfo
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"

#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "autoware_perception_msgs/msg/predicted_object.hpp"
#include "autoware_perception_msgs/msg/predicted_objects.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
Expand All @@ -26,8 +28,6 @@
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "tier4_debug_msgs/msg/float32_stamped.hpp"
#include "tier4_debug_msgs/msg/float64_stamped.hpp"
#include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp"
#include "tier4_planning_msgs/msg/velocity_limit.hpp"
#include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp"
Expand All @@ -37,6 +37,8 @@
#include <pcl/point_types.h>

using autoware::vehicle_info_utils::VehicleInfo;
using autoware_internal_debug_msgs::msg::Float32Stamped;
using autoware_internal_debug_msgs::msg::Float64Stamped;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
Expand All @@ -49,8 +51,6 @@ using geometry_msgs::msg::AccelWithCovarianceStamped;
using geometry_msgs::msg::Twist;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
using tier4_debug_msgs::msg::Float32Stamped;
using tier4_debug_msgs::msg::Float64Stamped;
using tier4_planning_msgs::msg::StopSpeedExceeded;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_obstacle_cruise_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
Expand All @@ -38,7 +39,6 @@
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_metric_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>
Expand Down

0 comments on commit b3c3f7a

Please sign in to comment.