Skip to content

Commit

Permalink
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil…
Browse files Browse the repository at this point in the history
…es planning/autoware_obstacle_stop_planner

Signed-off-by: vish0012 <[email protected]>
  • Loading branch information
vish0012 committed Jan 14, 2025
1 parent 1586372 commit 4878206
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 15 deletions.
2 changes: 1 addition & 1 deletion planning/autoware_obstacle_stop_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
Expand All @@ -40,7 +41,6 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ AdaptiveCruiseController::AdaptiveCruiseController(
param_.rough_velocity_rate = node_->declare_parameter<double>(acc_ns + "rough_velocity_rate");

/* publisher */
pub_debug_ = node_->create_publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>(
pub_debug_ = node_->create_publisher<autoware_internal_debug_msgs::msg::Float32MultiArrayStamped>(
"~/adaptive_cruise_control/debug_values", 1);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_debug_msgs/msg/float32_multi_array_stamped.hpp>

#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
Expand Down Expand Up @@ -58,7 +58,8 @@ class AdaptiveCruiseController
const PredictedObject & target_object);

private:
rclcpp::Publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr pub_debug_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr
pub_debug_;

rclcpp::Node * node_;
/*
Expand Down Expand Up @@ -217,7 +218,7 @@ class AdaptiveCruiseController
void registerQueToVelocity(const double vel, const rclcpp::Time & vel_time);

/* Debug */
mutable tier4_debug_msgs::msg::Float32MultiArrayStamped debug_values_;
mutable autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_values_;
enum DBGVAL {
ESTIMATED_VEL_PCL = 0,
ESTIMATED_VEL_OBJ = 1,
Expand Down
4 changes: 2 additions & 2 deletions planning/autoware_obstacle_stop_planner/src/debug_marker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@

#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
#include <autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
#include <autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <tier4_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

Expand All @@ -45,7 +45,7 @@ using visualization_msgs::msg::MarkerArray;
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
using autoware_adapi_v1_msgs::msg::VelocityFactor;
using autoware_adapi_v1_msgs::msg::VelocityFactorArray;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;

enum class PolygonType : int8_t { Vehicle = 0, Collision, SlowDownRange, SlowDown, Obstacle };

Expand Down
16 changes: 8 additions & 8 deletions planning/autoware_obstacle_stop_planner/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,17 @@
#include <pcl_ros/transforms.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/bool_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/float32_multi_array_stamped.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_objects.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <geometry_msgs/msg/accel_stamped.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_debug_msgs/msg/bool_stamped.hpp>
#include <tier4_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <tier4_planning_msgs/msg/expand_stop_range.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
Expand Down Expand Up @@ -81,13 +81,13 @@ using autoware::universe_utils::Point2d;
using autoware::universe_utils::Polygon2d;
using autoware::universe_utils::StopWatch;
using autoware::vehicle_info_utils::VehicleInfo;
using autoware_internal_debug_msgs::msg::BoolStamped;
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;
using autoware_internal_debug_msgs::msg::Float32Stamped;
using autoware_internal_debug_msgs::msg::Float64Stamped;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using tier4_debug_msgs::msg::BoolStamped;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_debug_msgs::msg::Float32Stamped;
using tier4_debug_msgs::msg::Float64Stamped;
using tier4_planning_msgs::msg::ExpandStopRange;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
Expand Down

0 comments on commit 4878206

Please sign in to comment.