Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_image_projection_based_fusion)!: tier4_debug-msgs changed to autoware_internal_debug_msgs in autoware_image_projection_based_fusion #9877

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_euclidean_cluster</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_lidar_centerpoint</depend>
<depend>autoware_object_recognition_utils</depend>
<depend>autoware_perception_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <Eigen/Geometry>
#include <autoware/image_projection_based_fusion/utils/utils.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <tier4_perception_msgs/msg/detected_object_with_feature.hpp>

#include <boost/optional.hpp>
Expand Down Expand Up @@ -253,12 +254,12 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::exportProcess()
std::chrono::nanoseconds(
(this->get_clock()->now() - cached_det3d_msg_ptr_->header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms",
processing_time_ms + stop_watch_ptr_->toc("processing_time", true));
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
processing_time_ms = 0;
}
Expand Down Expand Up @@ -353,9 +354,9 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::subCallback(
// add timestamp interval for debug
if (debug_internal_pub_) {
double timestamp_interval_ms = (matched_stamp - timestamp_nsec) / 1e6;
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms);
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms",
timestamp_interval_ms - det2d.input_offset_ms);
}
Expand Down Expand Up @@ -418,9 +419,9 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::roiCallback(

if (debug_internal_pub_) {
double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6;
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms);
debug_internal_pub_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_internal_pub_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms",
timestamp_interval_ms - det2d.input_offset_ms);
}
Expand Down
Loading