Skip to content

Commit 9a2ebcc

Browse files
authored
feat(autoware_surround_obstacle_checker): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_surround_obstacle_checker (#9915)
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_surround_obstacle_checker Signed-off-by: vish0012 <vishalchhn42@gmail.com>
1 parent 7f49688 commit 9a2ebcc

File tree

2 files changed

+6
-5
lines changed

2 files changed

+6
-5
lines changed

planning/autoware_surround_obstacle_checker/src/node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -81,8 +81,8 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio
8181
"~/output/velocity_limit_clear_command", rclcpp::QoS{1}.transient_local());
8282
pub_velocity_limit_ = this->create_publisher<VelocityLimit>(
8383
"~/output/max_velocity", rclcpp::QoS{1}.transient_local());
84-
pub_processing_time_ =
85-
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
84+
pub_processing_time_ = this->create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
85+
"~/debug/processing_time_ms", 1);
8686

8787
using std::chrono_literals::operator""ms;
8888
timer_ = rclcpp::create_timer(
@@ -231,7 +231,7 @@ void SurroundObstacleCheckerNode::onTimer()
231231
debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart);
232232
}
233233

234-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
234+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
235235
processing_time_msg.stamp = get_clock()->now();
236236
processing_time_msg.data = stop_watch.toc();
237237
pub_processing_time_->publish(processing_time_msg);

planning/autoware_surround_obstacle_checker/src/node.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,12 @@
2424
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
2525
#include <rclcpp/rclcpp.hpp>
2626

27+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2728
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2829
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
2930
#include <diagnostic_msgs/msg/key_value.hpp>
3031
#include <nav_msgs/msg/odometry.hpp>
3132
#include <sensor_msgs/msg/point_cloud2.hpp>
32-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
3333
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
3434
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
3535
#include <visualization_msgs/msg/marker_array.hpp>
@@ -106,7 +106,8 @@ class SurroundObstacleCheckerNode : public rclcpp::Node
106106
this, "~/input/objects"};
107107
rclcpp::Publisher<VelocityLimitClearCommand>::SharedPtr pub_clear_velocity_limit_;
108108
rclcpp::Publisher<VelocityLimit>::SharedPtr pub_velocity_limit_;
109-
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_;
109+
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
110+
pub_processing_time_;
110111

111112
// parameter callback result
112113
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

0 commit comments

Comments
 (0)