Skip to content

Commit ca3d90a

Browse files
committed
feat!: replace tier4_planning_msgs/VelocityLimit to autoware_internal_planning_msgs/VelocityLimit
Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>
1 parent 278e32d commit ca3d90a

9 files changed

+21
-21
lines changed

autoware_iv_internal_api_adaptor/src/velocity.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -27,11 +27,11 @@ Velocity::Velocity(const rclcpp::NodeOptions & options) : Node("external_api_vel
2727
srv_velocity_ = proxy.create_service<tier4_external_api_msgs::srv::SetVelocityLimit>(
2828
"/api/autoware/set/velocity_limit", std::bind(&Velocity::setVelocityLimit, this, _1, _2));
2929

30-
pub_api_velocity_ = create_publisher<tier4_planning_msgs::msg::VelocityLimit>(
30+
pub_api_velocity_ = create_publisher<autoware_internal_planning_msgs::msg::VelocityLimit>(
3131
"/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>(
3333
"/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>(
3535
"/planning/scenario_planning/current_max_velocity", rclcpp::QoS(1).transient_local(),
3636
std::bind(&Velocity::onVelocityLimit, this, _1));
3737

@@ -63,7 +63,7 @@ void Velocity::setVelocityLimit(
6363
response->status = tier4_api_utils::response_success();
6464
}
6565

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)
6767
{
6868
// store the velocity for releasing the stop
6969
if (kVelocityEpsilon < msg->max_velocity) {
@@ -75,15 +75,15 @@ void Velocity::onVelocityLimit(const tier4_planning_msgs::msg::VelocityLimit::Sh
7575

7676
void Velocity::publishApiVelocity(double velocity)
7777
{
78-
tier4_planning_msgs::msg::VelocityLimit msg;
78+
autoware_internal_planning_msgs::msg::VelocityLimit msg;
7979
msg.stamp = now();
8080
msg.max_velocity = velocity;
8181
pub_api_velocity_->publish(msg);
8282
}
8383

8484
void Velocity::publishPlanningVelocity(double velocity)
8585
{
86-
tier4_planning_msgs::msg::VelocityLimit msg;
86+
autoware_internal_planning_msgs::msg::VelocityLimit msg;
8787
msg.stamp = now();
8888
msg.max_velocity = velocity;
8989
pub_planning_velocity_->publish(msg);

autoware_iv_internal_api_adaptor/src/velocity.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020

2121
#include <tier4_external_api_msgs/srv/pause_driving.hpp>
2222
#include <tier4_external_api_msgs/srv/set_velocity_limit.hpp>
23-
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
23+
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
2424

2525
namespace internal_api
2626
{
@@ -32,7 +32,7 @@ class Velocity : public rclcpp::Node
3232
private:
3333
using PauseDriving = tier4_external_api_msgs::srv::PauseDriving;
3434
using SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit;
35-
using VelocityLimit = tier4_planning_msgs::msg::VelocityLimit;
35+
using VelocityLimit = autoware_internal_planning_msgs::msg::VelocityLimit;
3636

3737
// ros interface
3838
tier4_api_utils::Service<PauseDriving>::SharedPtr srv_pause_;
@@ -55,7 +55,7 @@ class Velocity : public rclcpp::Node
5555
void setVelocityLimit(
5656
const tier4_external_api_msgs::srv::SetVelocityLimit::Request::SharedPtr request,
5757
const tier4_external_api_msgs::srv::SetVelocityLimit::Response::SharedPtr response);
58-
void onVelocityLimit(const tier4_planning_msgs::msg::VelocityLimit::SharedPtr msg);
58+
void onVelocityLimit(const autoware_internal_planning_msgs::msg::VelocityLimit::SharedPtr msg);
5959

6060
// class method
6161
void publishApiVelocity(double velocity);

awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ class AutowareIvAutowareStatePublisher
5858
const autoware_adapi_v1_msgs::msg::MrmState::ConstSharedPtr & mrm_state_ptr,
5959
tier4_api_msgs::msg::AwapiAutowareStatus * status);
6060
void getCurrentMaxVelInfo(
61-
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr & current_max_velocity_ptr,
61+
const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr & current_max_velocity_ptr,
6262
tier4_api_msgs::msg::AwapiAutowareStatus * status);
6363
void getHazardStatusInfo(
6464
const AutowareInfo & aw_info, tier4_api_msgs::msg::AwapiAutowareStatus * status);

awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
#include <tier4_planning_msgs/msg/is_avoidance_possible.hpp>
3838
#include <tier4_planning_msgs/msg/lane_change_status.hpp>
3939
#include <tier4_planning_msgs/msg/stop_reason_array.hpp>
40-
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
40+
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
4141
#include <tier4_system_msgs/msg/autoware_state.hpp>
4242
#include <tier4_v2x_msgs/msg/infrastructure_command_array.hpp>
4343
#include <tier4_v2x_msgs/msg/virtual_traffic_light_state_array.hpp>
@@ -85,7 +85,7 @@ struct AutowareInfo
8585
tier4_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr obstacle_avoid_ready_ptr;
8686
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr obstacle_avoid_candidate_ptr;
8787
tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr max_velocity_ptr;
88-
tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr current_max_velocity_ptr;
88+
autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr current_max_velocity_ptr;
8989
tier4_api_msgs::msg::StopCommand::ConstSharedPtr temporary_stop_ptr;
9090
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr autoware_planning_traj_ptr;
9191
};

awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ class AutowareIvAdapter : public rclcpp::Node
9292
rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr
9393
sub_obstacle_avoid_candidate_;
9494
rclcpp::Subscription<tier4_api_msgs::msg::VelocityLimit>::SharedPtr sub_max_velocity_;
95-
rclcpp::Subscription<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr
95+
rclcpp::Subscription<autoware_internal_planning_msgs::msg::VelocityLimit>::SharedPtr
9696
sub_current_max_velocity_;
9797
rclcpp::Subscription<tier4_api_msgs::msg::StopCommand>::SharedPtr sub_temporary_stop_;
9898
rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr sub_autoware_traj_;
@@ -145,7 +145,7 @@ class AutowareIvAdapter : public rclcpp::Node
145145
const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);
146146
void callbackMaxVelocity(const tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr);
147147
void callbackCurrentMaxVelocity(
148-
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr);
148+
const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr);
149149
void callbackTemporaryStop(const tier4_api_msgs::msg::StopCommand::ConstSharedPtr msg_ptr);
150150
void callbackAutowareTrajectory(
151151
const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);

awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_max_velocity_publisher.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
#include <rclcpp/rclcpp.hpp>
2121

22-
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
22+
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
2323

2424
namespace autoware_api
2525
{
@@ -33,7 +33,7 @@ class AutowareIvMaxVelocityPublisher
3333
rclcpp::Clock::SharedPtr clock_;
3434

3535
// publisher
36-
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr pub_state_;
36+
rclcpp::Publisher<autoware_internal_planning_msgs::msg::VelocityLimit>::SharedPtr pub_state_;
3737

3838
bool calcMaxVelocity(
3939
const tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr & max_velocity_ptr,

awapi_awiv_adapter/src/awapi_autoware_state_publisher.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,7 @@ void AutowareIvAutowareStatePublisher::getEmergencyStateInfo(
114114
}
115115

116116
void AutowareIvAutowareStatePublisher::getCurrentMaxVelInfo(
117-
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr & current_max_velocity_ptr,
117+
const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr & current_max_velocity_ptr,
118118
tier4_api_msgs::msg::AwapiAutowareStatus * status)
119119
{
120120
if (!current_max_velocity_ptr) {

awapi_awiv_adapter/src/awapi_awiv_adapter_core.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,7 @@ AutowareIvAdapter::AutowareIvAdapter()
116116
std::bind(&AutowareIvAdapter::callbackLaneObstacleAvoidCandidatePath, this, _1));
117117
sub_max_velocity_ = this->create_subscription<tier4_api_msgs::msg::VelocityLimit>(
118118
"input/max_velocity", 1, std::bind(&AutowareIvAdapter::callbackMaxVelocity, this, _1));
119-
sub_current_max_velocity_ = this->create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
119+
sub_current_max_velocity_ = this->create_subscription<autoware_internal_planning_msgs::msg::VelocityLimit>(
120120
"input/current_max_velocity", durable_qos,
121121
std::bind(&AutowareIvAdapter::callbackCurrentMaxVelocity, this, _1));
122122
sub_temporary_stop_ = this->create_subscription<tier4_api_msgs::msg::StopCommand>(
@@ -323,7 +323,7 @@ void AutowareIvAdapter::callbackMaxVelocity(
323323
}
324324

325325
void AutowareIvAdapter::callbackCurrentMaxVelocity(
326-
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr)
326+
const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr)
327327
{
328328
aw_info_.current_max_velocity_ptr = msg_ptr;
329329
}

awapi_awiv_adapter/src/awapi_max_velocity_publisher.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,13 +21,13 @@ AutowareIvMaxVelocityPublisher::AutowareIvMaxVelocityPublisher(
2121
: clock_(node.get_clock()), default_max_velocity_(default_max_velocity)
2222
{
2323
// publisher
24-
pub_state_ = node.create_publisher<tier4_planning_msgs::msg::VelocityLimit>(
24+
pub_state_ = node.create_publisher<autoware_internal_planning_msgs::msg::VelocityLimit>(
2525
"output/max_velocity", rclcpp::QoS{1}.transient_local());
2626
}
2727

2828
void AutowareIvMaxVelocityPublisher::statePublisher(const AutowareInfo & aw_info)
2929
{
30-
tier4_planning_msgs::msg::VelocityLimit max_velocity;
30+
autoware_internal_planning_msgs::msg::VelocityLimit max_velocity;
3131
if (calcMaxVelocity(
3232
aw_info.max_velocity_ptr, aw_info.temporary_stop_ptr,
3333
&max_velocity.max_velocity)) // publish info

0 commit comments

Comments
 (0)