Skip to content

Commit 8865d0f

Browse files
authored
feat(motion_velocity_planner): use Float64Stamped in autoware_internal_debug_msgs (#9745)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent c16e656 commit 8865d0f

File tree

8 files changed

+23
-17
lines changed

8 files changed

+23
-17
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,9 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo
5151
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/" + ns_ + "/virtual_walls", 1);
5252
processing_diag_publisher_ = std::make_shared<autoware::universe_utils::ProcessingTimePublisher>(
5353
&node, "~/debug/" + ns_ + "/processing_time_ms_diag");
54-
processing_time_publisher_ = node.create_publisher<tier4_debug_msgs::msg::Float64Stamped>(
55-
"~/debug/" + ns_ + "/processing_time_ms", 1);
54+
processing_time_publisher_ =
55+
node.create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
56+
"~/debug/" + ns_ + "/processing_time_ms", 1);
5657

5758
using autoware::universe_utils::getOrDeclareParameter;
5859
auto & p = params_;
@@ -190,7 +191,7 @@ VelocityPlanningResult DynamicObstacleStopModule::plan(
190191
processing_times["collisions"] = collisions_duration_us / 1000;
191192
processing_times["Total"] = total_time_us / 1000;
192193
processing_diag_publisher_->publish(processing_times);
193-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
194+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
194195
processing_time_msg.stamp = clock_->now();
195196
processing_time_msg.data = processing_times["Total"];
196197
processing_time_publisher_->publish(processing_time_msg);

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,9 @@ void ObstacleVelocityLimiterModule::init(rclcpp::Node & node, const std::string
5656
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/" + ns_ + "/virtual_walls", 1);
5757
processing_diag_publisher_ = std::make_shared<autoware::universe_utils::ProcessingTimePublisher>(
5858
&node, "~/debug/" + ns_ + "/processing_time_ms_diag");
59-
processing_time_publisher_ = node.create_publisher<tier4_debug_msgs::msg::Float64Stamped>(
60-
"~/debug/" + ns_ + "/processing_time_ms", 1);
59+
processing_time_publisher_ =
60+
node.create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
61+
"~/debug/" + ns_ + "/processing_time_ms", 1);
6162

6263
const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
6364
vehicle_lateral_offset_ = static_cast<double>(vehicle_info.max_lateral_offset_m);
@@ -236,7 +237,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan(
236237
processing_times["slowdowns"] = slowdowns_us / 1000;
237238
processing_times["Total"] = total_us / 1000;
238239
processing_diag_publisher_->publish(processing_times);
239-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
240+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
240241
processing_time_msg.stamp = clock_->now();
241242
processing_time_msg.data = processing_times["Total"];
242243
processing_time_publisher_->publish(processing_time_msg);

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,9 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name)
6666
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/" + ns_ + "/virtual_walls", 1);
6767
processing_diag_publisher_ = std::make_shared<universe_utils::ProcessingTimePublisher>(
6868
&node, "~/debug/" + ns_ + "/processing_time_ms_diag");
69-
processing_time_publisher_ = node.create_publisher<tier4_debug_msgs::msg::Float64Stamped>(
70-
"~/debug/" + ns_ + "/processing_time_ms", 1);
69+
processing_time_publisher_ =
70+
node.create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
71+
"~/debug/" + ns_ + "/processing_time_ms", 1);
7172
}
7273
void OutOfLaneModule::init_parameters(rclcpp::Node & node)
7374
{
@@ -349,7 +350,7 @@ VelocityPlanningResult OutOfLaneModule::plan(
349350
processing_times["publish_markers"] = pub_markers_us / 1000;
350351
processing_times["Total"] = total_time_us / 1000;
351352
processing_diag_publisher_->publish(processing_times);
352-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
353+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
353354
processing_time_msg.stamp = clock_->now();
354355
processing_time_msg.data = processing_times["Total"];
355356
processing_time_publisher_->publish(processing_time_msg);

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,8 @@
2222
#include <autoware/universe_utils/ros/processing_time_publisher.hpp>
2323
#include <rclcpp/rclcpp.hpp>
2424

25+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2526
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
26-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
2727

2828
#include <memory>
2929
#include <string>
@@ -47,7 +47,8 @@ class PluginModuleInterface
4747
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_publisher_;
4848
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr virtual_wall_publisher_;
4949
std::shared_ptr<autoware::universe_utils::ProcessingTimePublisher> processing_diag_publisher_;
50-
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_publisher_;
50+
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
51+
processing_time_publisher_;
5152
autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{};
5253
};
5354

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
1818

1919
<depend>autoware_behavior_velocity_planner_common</depend>
20+
<depend>autoware_internal_debug_msgs</depend>
2021
<depend>autoware_motion_utils</depend>
2122
<depend>autoware_perception_msgs</depend>
2223
<depend>autoware_planning_msgs</depend>
@@ -27,7 +28,6 @@
2728
<depend>geometry_msgs</depend>
2829
<depend>libboost-dev</depend>
2930
<depend>rclcpp</depend>
30-
<depend>tier4_debug_msgs</depend>
3131
<depend>tier4_planning_msgs</depend>
3232
<depend>visualization_msgs</depend>
3333

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818

1919
<build_depend>rosidl_default_generators</build_depend>
2020

21+
<depend>autoware_internal_debug_msgs</depend>
2122
<depend>autoware_map_msgs</depend>
2223
<depend>autoware_motion_utils</depend>
2324
<depend>autoware_motion_velocity_planner_common</depend>
@@ -37,7 +38,6 @@
3738
<depend>tf2_eigen</depend>
3839
<depend>tf2_geometry_msgs</depend>
3940
<depend>tf2_ros</depend>
40-
<depend>tier4_debug_msgs</depend>
4141
<depend>tier4_metric_msgs</depend>
4242
<depend>tier4_planning_msgs</depend>
4343
<depend>visualization_msgs</depend>

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,8 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions &
8686
this->create_publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>(
8787
"~/output/velocity_factors", 1);
8888
processing_time_publisher_ =
89-
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
89+
this->create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
90+
"~/debug/processing_time_ms", 1);
9091
debug_viz_pub_ =
9192
this->create_publisher<visualization_msgs::msg::MarkerArray>("~/debug/markers", 1);
9293
metrics_pub_ = this->create_publisher<MetricArray>("~/metrics", 1);
@@ -299,7 +300,7 @@ void MotionVelocityPlannerNode::on_trajectory(
299300
trajectory_pub_, output_trajectory_msg.header.stamp);
300301
processing_times["Total"] = stop_watch.toc("Total");
301302
processing_diag_publisher_.publish(processing_times);
302-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
303+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
303304
processing_time_msg.stamp = get_clock()->now();
304305
processing_time_msg.data = processing_times["Total"];
305306
processing_time_publisher_->publish(processing_time_msg);

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -25,14 +25,14 @@
2525
#include <autoware_motion_velocity_planner_node/srv/unload_plugin.hpp>
2626
#include <rclcpp/rclcpp.hpp>
2727

28+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2829
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
2930
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
3031
#include <autoware_perception_msgs/msg/traffic_signal_array.hpp>
3132
#include <autoware_planning_msgs/msg/trajectory.hpp>
3233
#include <nav_msgs/msg/occupancy_grid.hpp>
3334
#include <nav_msgs/msg/odometry.hpp>
3435
#include <sensor_msgs/msg/point_cloud2.hpp>
35-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
3636
#include <visualization_msgs/msg/marker_array.hpp>
3737

3838
#include <tf2_ros/buffer.h>
@@ -97,7 +97,8 @@ class MotionVelocityPlannerNode : public rclcpp::Node
9797
velocity_factor_publisher_;
9898
autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{
9999
this, "~/debug/processing_time_ms_diag"};
100-
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_publisher_;
100+
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
101+
processing_time_publisher_;
101102
autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this};
102103
rclcpp::Publisher<MetricArray>::SharedPtr metrics_pub_;
103104

0 commit comments

Comments
 (0)