Skip to content

Commit b22a5b7

Browse files
authored
Merge branch 'main' into fix/distortion_corrector_node
2 parents e7980ee + 598d937 commit b22a5b7

File tree

2 files changed

+4
-3
lines changed
  • planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src

2 files changed

+4
-3
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -83,8 +83,8 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions &
8383
velocity_factor_publisher_ =
8484
this->create_publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>(
8585
"~/output/velocity_factors", 1);
86-
processing_time_publisher_ = this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>(
87-
"~/debug/total_time/processing_time_ms", 1);
86+
processing_time_publisher_ =
87+
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
8888

8989
// Parameters
9090
smooth_velocity_before_planning_ = declare_parameter<bool>("smooth_velocity_before_planning");

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,8 @@ class MotionVelocityPlannerNode : public rclcpp::Node
9797
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_viz_pub_;
9898
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>::SharedPtr
9999
velocity_factor_publisher_;
100-
autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{this};
100+
autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{
101+
this, "~/debug/processing_time_ms_diag"};
101102
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_publisher_;
102103
autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this};
103104

0 commit comments

Comments
 (0)