Skip to content

Commit 708fa76

Browse files
authored
feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perc… (#9879)
feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perception/autoware_multi_object_tracker Signed-off-by: vish0012 <vishalchhn42@gmail.com>
1 parent 51818f0 commit 708fa76

File tree

1 file changed

+6
-6
lines changed
  • perception/autoware_multi_object_tracker/src/debugger

1 file changed

+6
-6
lines changed

perception/autoware_multi_object_tracker/src/debugger/debugger.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,7 @@ void TrackerDebugger::startMeasurementTime(
127127
stamp_process_start_ = now;
128128
if (debug_settings_.publish_processing_time) {
129129
double input_latency_ms = (now - last_input_stamp_).seconds() * 1e3;
130-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
130+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
131131
"debug/input_latency_ms", input_latency_ms);
132132
}
133133
// initialize debug time stamps
@@ -169,15 +169,15 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim
169169
double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3;
170170

171171
// starting from the measurement time
172-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
172+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
173173
"debug/pipeline_latency_ms", pipeline_latency_ms_);
174-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
174+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
175175
"debug/cyclic_time_ms", cyclic_time_ms);
176-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
176+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
177177
"debug/processing_time_ms", processing_time_ms);
178-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
178+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
179179
"debug/processing_latency_ms", processing_latency_ms);
180-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
180+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
181181
"debug/meas_to_tracked_object_ms", measurement_to_object_ms);
182182
}
183183
stamp_publish_output_ = now;

0 commit comments

Comments
 (0)