Skip to content

Commit e60c867

Browse files
authored
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (#9875)
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_map_based_prediction Signed-off-by: vish0012 <vishalchhn42@gmail.com>
1 parent 708fa76 commit e60c867

File tree

3 files changed

+4
-4
lines changed

3 files changed

+4
-4
lines changed

perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -71,8 +71,8 @@ struct hash<lanelet::routing::LaneletPath>
7171
} // namespace std
7272
namespace autoware::map_based_prediction
7373
{
74+
using autoware_internal_debug_msgs::msg::StringStamped;
7475
using autoware_planning_msgs::msg::TrajectoryPoint;
75-
using tier4_debug_msgs::msg::StringStamped;
7676
using TrajectoryPoints = std::vector<TrajectoryPoint>;
7777

7878
class MapBasedPredictionNode : public rclcpp::Node

perception/autoware_map_based_prediction/package.xml

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

19+
<depend>autoware_internal_debug_msgs</depend>
1920
<depend>autoware_interpolation</depend>
2021
<depend>autoware_lanelet2_extension</depend>
2122
<depend>autoware_motion_utils</depend>
@@ -27,7 +28,6 @@
2728
<depend>tf2</depend>
2829
<depend>tf2_geometry_msgs</depend>
2930
<depend>tf2_ros</depend>
30-
<depend>tier4_debug_msgs</depend>
3131
<depend>unique_identifier_msgs</depend>
3232
<depend>visualization_msgs</depend>
3333

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -670,9 +670,9 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
670670
if (stop_watch_ptr_) {
671671
const auto processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
672672
const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
673-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
673+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
674674
"debug/cyclic_time_ms", cyclic_time_ms);
675-
processing_time_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
675+
processing_time_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
676676
"debug/processing_time_ms", processing_time_ms);
677677
}
678678
}

0 commit comments

Comments
 (0)