Commit 9a2ebcc 1 parent 7f49688 commit 9a2ebcc Copy full SHA for 9a2ebcc
File tree 2 files changed +6
-5
lines changed
planning/autoware_surround_obstacle_checker/src
2 files changed +6
-5
lines changed Original file line number Diff line number Diff line change @@ -81,8 +81,8 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio
81
81
" ~/output/velocity_limit_clear_command" , rclcpp::QoS{1 }.transient_local ());
82
82
pub_velocity_limit_ = this ->create_publisher <VelocityLimit>(
83
83
" ~/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 );
86
86
87
87
using std::chrono_literals::operator " " ms;
88
88
timer_ = rclcpp::create_timer (
@@ -231,7 +231,7 @@ void SurroundObstacleCheckerNode::onTimer()
231
231
debug_ptr_->pushPose (odometry_ptr_->pose .pose , PoseType::NoStart);
232
232
}
233
233
234
- tier4_debug_msgs ::msg::Float64Stamped processing_time_msg;
234
+ autoware_internal_debug_msgs ::msg::Float64Stamped processing_time_msg;
235
235
processing_time_msg.stamp = get_clock ()->now ();
236
236
processing_time_msg.data = stop_watch.toc ();
237
237
pub_processing_time_->publish (processing_time_msg);
Original file line number Diff line number Diff line change 24
24
#include < autoware_vehicle_info_utils/vehicle_info_utils.hpp>
25
25
#include < rclcpp/rclcpp.hpp>
26
26
27
+ #include < autoware_internal_debug_msgs/msg/float64_stamped.hpp>
27
28
#include < autoware_perception_msgs/msg/predicted_objects.hpp>
28
29
#include < diagnostic_msgs/msg/diagnostic_status.hpp>
29
30
#include < diagnostic_msgs/msg/key_value.hpp>
30
31
#include < nav_msgs/msg/odometry.hpp>
31
32
#include < sensor_msgs/msg/point_cloud2.hpp>
32
- #include < tier4_debug_msgs/msg/float64_stamped.hpp>
33
33
#include < tier4_planning_msgs/msg/velocity_limit.hpp>
34
34
#include < tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
35
35
#include < visualization_msgs/msg/marker_array.hpp>
@@ -106,7 +106,8 @@ class SurroundObstacleCheckerNode : public rclcpp::Node
106
106
this , " ~/input/objects" };
107
107
rclcpp::Publisher<VelocityLimitClearCommand>::SharedPtr pub_clear_velocity_limit_;
108
108
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_;
110
111
111
112
// parameter callback result
112
113
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
You can’t perform that action at this time.
0 commit comments