Skip to content

Commit c31c0ee

Browse files
authoredMar 11, 2025··
fix(dynamic_obstacle_stop): publish processing time when early return (#10254)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 1b37970 commit c31c0ee

File tree

2 files changed

+16
-8
lines changed

2 files changed

+16
-8
lines changed
 

‎planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp

+14-7
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@
3232
#include <map>
3333
#include <memory>
3434
#include <string>
35-
#include <utility>
3635
#include <vector>
3736

3837
namespace autoware::motion_velocity_planner
@@ -97,6 +96,14 @@ void DynamicObstacleStopModule::update_parameters(const std::vector<rclcpp::Para
9796
update_param(parameters, ns_ + ".ignore_unavoidable_collisions", p.ignore_unavoidable_collisions);
9897
}
9998

99+
void DynamicObstacleStopModule::publish_processing_time(const double processing_time_ms)
100+
{
101+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
102+
processing_time_msg.stamp = clock_->now();
103+
processing_time_msg.data = processing_time_ms;
104+
processing_time_publisher_->publish(processing_time_msg);
105+
}
106+
100107
VelocityPlanningResult DynamicObstacleStopModule::plan(
101108
[[maybe_unused]] const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> &
102109
raw_trajectory_points,
@@ -105,9 +112,12 @@ VelocityPlanningResult DynamicObstacleStopModule::plan(
105112
{
106113
VelocityPlanningResult result;
107114
debug_data_.reset_data();
108-
if (smoothed_trajectory_points.size() < 2) return result;
109-
110115
autoware_utils::StopWatch<std::chrono::microseconds> stopwatch;
116+
if (smoothed_trajectory_points.size() < 2) {
117+
publish_processing_time(stopwatch.toc() / 1000);
118+
return result;
119+
}
120+
111121
stopwatch.tic();
112122
stopwatch.tic("preprocessing");
113123
dynamic_obstacle_stop::EgoData ego_data;
@@ -191,10 +201,7 @@ VelocityPlanningResult DynamicObstacleStopModule::plan(
191201
processing_times["collisions"] = collisions_duration_us / 1000;
192202
processing_times["Total"] = total_time_us / 1000;
193203
processing_diag_publisher_->publish(processing_times);
194-
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
195-
processing_time_msg.stamp = clock_->now();
196-
processing_time_msg.data = processing_times["Total"];
197-
processing_time_publisher_->publish(processing_time_msg);
204+
publish_processing_time(processing_times["Total"]);
198205
return result;
199206
}
200207

‎planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ class DynamicObstacleStopModule : public PluginModuleInterface
3535
void init(rclcpp::Node & node, const std::string & module_name) override;
3636
void publish_planning_factor() override { planning_factor_interface_->publish(); };
3737
void update_parameters(const std::vector<rclcpp::Parameter> & parameters) override;
38+
void publish_processing_time(const double processing_time_ms);
3839
VelocityPlanningResult plan(
3940
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & raw_trajectory_points,
4041
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & smoothed_trajectory_points,
@@ -47,7 +48,7 @@ class DynamicObstacleStopModule : public PluginModuleInterface
4748

4849
inline static const std::string ns_ = "dynamic_obstacle_stop";
4950
std::string module_name_;
50-
rclcpp::Clock::SharedPtr clock_{};
51+
rclcpp::Clock::SharedPtr clock_;
5152

5253
dynamic_obstacle_stop::PlannerParam params_;
5354
dynamic_obstacle_stop::ObjectStopDecisionMap object_map_;

0 commit comments

Comments
 (0)
Please sign in to comment.