@@ -27,11 +27,11 @@ Velocity::Velocity(const rclcpp::NodeOptions & options) : Node("external_api_vel
27
27
srv_velocity_ = proxy.create_service <tier4_external_api_msgs::srv::SetVelocityLimit>(
28
28
" /api/autoware/set/velocity_limit" , std::bind (&Velocity::setVelocityLimit, this , _1, _2));
29
29
30
- pub_api_velocity_ = create_publisher<tier4_planning_msgs ::msg::VelocityLimit>(
30
+ pub_api_velocity_ = create_publisher<autoware_internal_planning_msgs ::msg::VelocityLimit>(
31
31
" /api/autoware/get/velocity_limit" , rclcpp::QoS (1 ).transient_local ());
32
- pub_planning_velocity_ = create_publisher<tier4_planning_msgs ::msg::VelocityLimit>(
32
+ pub_planning_velocity_ = create_publisher<autoware_internal_planning_msgs ::msg::VelocityLimit>(
33
33
" /planning/scenario_planning/max_velocity_default" , rclcpp::QoS (1 ).transient_local ());
34
- sub_planning_velocity_ = create_subscription<tier4_planning_msgs ::msg::VelocityLimit>(
34
+ sub_planning_velocity_ = create_subscription<autoware_internal_planning_msgs ::msg::VelocityLimit>(
35
35
" /planning/scenario_planning/current_max_velocity" , rclcpp::QoS (1 ).transient_local (),
36
36
std::bind (&Velocity::onVelocityLimit, this , _1));
37
37
@@ -63,7 +63,7 @@ void Velocity::setVelocityLimit(
63
63
response->status = tier4_api_utils::response_success ();
64
64
}
65
65
66
- void Velocity::onVelocityLimit (const tier4_planning_msgs ::msg::VelocityLimit::SharedPtr msg)
66
+ void Velocity::onVelocityLimit (const autoware_internal_planning_msgs ::msg::VelocityLimit::SharedPtr msg)
67
67
{
68
68
// store the velocity for releasing the stop
69
69
if (kVelocityEpsilon < msg->max_velocity ) {
@@ -75,15 +75,15 @@ void Velocity::onVelocityLimit(const tier4_planning_msgs::msg::VelocityLimit::Sh
75
75
76
76
void Velocity::publishApiVelocity (double velocity)
77
77
{
78
- tier4_planning_msgs ::msg::VelocityLimit msg;
78
+ autoware_internal_planning_msgs ::msg::VelocityLimit msg;
79
79
msg.stamp = now ();
80
80
msg.max_velocity = velocity;
81
81
pub_api_velocity_->publish (msg);
82
82
}
83
83
84
84
void Velocity::publishPlanningVelocity (double velocity)
85
85
{
86
- tier4_planning_msgs ::msg::VelocityLimit msg;
86
+ autoware_internal_planning_msgs ::msg::VelocityLimit msg;
87
87
msg.stamp = now ();
88
88
msg.max_velocity = velocity;
89
89
pub_planning_velocity_->publish (msg);
0 commit comments