Skip to content

Commit 8eed7e9

Browse files
authored
feat(autoware_image_projection_based_fusion)!: tier4_debug-msgs changed to autoware_internal_debug_msgs in autoware_image_projection_based_fusion (autowarefoundation#9877)
Signed-off-by: vish0012 <vishalchhn42@gmail.com>
1 parent 24f2656 commit 8eed7e9

File tree

2 files changed

+9
-7
lines changed

2 files changed

+9
-7
lines changed

perception/autoware_image_projection_based_fusion/package.xml

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

1919
<depend>autoware_euclidean_cluster</depend>
20+
<depend>autoware_internal_debug_msgs</depend>
2021
<depend>autoware_lidar_centerpoint</depend>
2122
<depend>autoware_object_recognition_utils</depend>
2223
<depend>autoware_perception_msgs</depend>

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <Eigen/Geometry>
2121
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
2222

23+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2324
#include <tier4_perception_msgs/msg/detected_object_with_feature.hpp>
2425

2526
#include <boost/optional.hpp>
@@ -253,12 +254,12 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::exportProcess()
253254
std::chrono::nanoseconds(
254255
(this->get_clock()->now() - cached_det3d_msg_ptr_->header.stamp).nanoseconds()))
255256
.count();
256-
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
257+
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
257258
"debug/cyclic_time_ms", cyclic_time_ms);
258-
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
259+
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
259260
"debug/processing_time_ms",
260261
processing_time_ms + stop_watch_ptr_->toc("processing_time", true));
261-
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
262+
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
262263
"debug/pipeline_latency_ms", pipeline_latency_ms);
263264
processing_time_ms = 0;
264265
}
@@ -353,9 +354,9 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::subCallback(
353354
// add timestamp interval for debug
354355
if (debug_internal_pub_) {
355356
double timestamp_interval_ms = (matched_stamp - timestamp_nsec) / 1e6;
356-
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
357+
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
357358
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms);
358-
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
359+
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
359360
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms",
360361
timestamp_interval_ms - det2d.input_offset_ms);
361362
}
@@ -418,9 +419,9 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::roiCallback(
418419

419420
if (debug_internal_pub_) {
420421
double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6;
421-
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
422+
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
422423
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms);
423-
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
424+
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
424425
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms",
425426
timestamp_interval_ms - det2d.input_offset_ms);
426427
}

0 commit comments

Comments
 (0)