From 4952058b2a8077c01740855f831e14d69a1f4fb2 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Mon, 11 Nov 2024 13:52:41 +0100 Subject: [PATCH] chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs Signed-off-by: Esteve Fernandez --- common/tier4_adapi_rviz_plugin/package.xml | 2 +- .../src/door_panel.hpp | 8 ++--- .../src/route_panel.hpp | 8 ++--- .../tier4_camera_view_rviz_plugin/package.xml | 2 +- system/autoware_default_adapi/package.xml | 2 +- .../src/compatibility/autoware_state.hpp | 18 +++++----- .../autoware_default_adapi/src/fail_safe.hpp | 6 ++-- .../autoware_default_adapi/src/heartbeat.cpp | 2 +- .../autoware_default_adapi/src/heartbeat.hpp | 4 +-- .../autoware_default_adapi/src/interface.hpp | 4 +-- .../src/localization.cpp | 4 +-- .../src/localization.hpp | 10 +++--- system/autoware_default_adapi/src/motion.cpp | 8 ++--- system/autoware_default_adapi/src/motion.hpp | 10 +++--- .../src/operation_mode.hpp | 30 ++++++++-------- .../autoware_default_adapi/src/perception.cpp | 2 +- .../autoware_default_adapi/src/perception.hpp | 4 +-- .../autoware_default_adapi/src/planning.hpp | 6 ++-- system/autoware_default_adapi/src/routing.cpp | 28 +++++++-------- system/autoware_default_adapi/src/routing.hpp | 36 +++++++++---------- system/autoware_default_adapi/src/vehicle.cpp | 4 +-- system/autoware_default_adapi/src/vehicle.hpp | 6 ++-- .../src/vehicle_door.hpp | 8 ++--- .../src/vehicle_info.hpp | 4 +-- .../ad_api_adaptors/package.xml | 2 +- .../src/initial_pose_adaptor.hpp | 4 +-- .../ad_api_adaptors/src/routing_adaptor.hpp | 10 +++--- .../automatic_pose_initializer/package.xml | 2 +- .../src/automatic_pose_initializer.hpp | 6 ++-- 29 files changed, 120 insertions(+), 120 deletions(-) diff --git a/common/tier4_adapi_rviz_plugin/package.xml b/common/tier4_adapi_rviz_plugin/package.xml index d7269377829dc..c31e19919ff22 100644 --- a/common/tier4_adapi_rviz_plugin/package.xml +++ b/common/tier4_adapi_rviz_plugin/package.xml @@ -12,7 +12,7 @@ ament_cmake_auto autoware_cmake - autoware_ad_api_specs + autoware_adapi_specs autoware_component_interface_utils autoware_vehicle_msgs geometry_msgs diff --git a/common/tier4_adapi_rviz_plugin/src/door_panel.hpp b/common/tier4_adapi_rviz_plugin/src/door_panel.hpp index 1ce1d2b1d577c..3ace533eada50 100644 --- a/common/tier4_adapi_rviz_plugin/src/door_panel.hpp +++ b/common/tier4_adapi_rviz_plugin/src/door_panel.hpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include #include #include @@ -31,9 +31,9 @@ namespace tier4_adapi_rviz_plugins class DoorPanel : public rviz_common::Panel { Q_OBJECT - using DoorCommand = autoware::ad_api_specs::vehicle::DoorCommand; - using DoorLayout = autoware::ad_api_specs::vehicle::DoorLayout; - using DoorStatus = autoware::ad_api_specs::vehicle::DoorStatus; + using DoorCommand = autoware::adapi_specs::vehicle::DoorCommand; + using DoorLayout = autoware::adapi_specs::vehicle::DoorLayout; + using DoorStatus = autoware::adapi_specs::vehicle::DoorStatus; public: explicit DoorPanel(QWidget * parent = nullptr); diff --git a/common/tier4_adapi_rviz_plugin/src/route_panel.hpp b/common/tier4_adapi_rviz_plugin/src/route_panel.hpp index a28357317492b..78fda2852d2c2 100644 --- a/common/tier4_adapi_rviz_plugin/src/route_panel.hpp +++ b/common/tier4_adapi_rviz_plugin/src/route_panel.hpp @@ -20,7 +20,7 @@ #include #include #include -#include +#include #include #include #include @@ -35,9 +35,9 @@ namespace tier4_adapi_rviz_plugins class RoutePanel : public rviz_common::Panel { Q_OBJECT - using ClearRoute = autoware::ad_api_specs::routing::ClearRoute; - using SetRoutePoints = autoware::ad_api_specs::routing::SetRoutePoints; - using ChangeRoutePoints = autoware::ad_api_specs::routing::ChangeRoutePoints; + using ClearRoute = autoware::adapi_specs::routing::ClearRoute; + using SetRoutePoints = autoware::adapi_specs::routing::SetRoutePoints; + using ChangeRoutePoints = autoware::adapi_specs::routing::ChangeRoutePoints; using PoseStamped = geometry_msgs::msg::PoseStamped; public: diff --git a/common/tier4_camera_view_rviz_plugin/package.xml b/common/tier4_camera_view_rviz_plugin/package.xml index d36c9eae781c6..7c85d9f84871a 100644 --- a/common/tier4_camera_view_rviz_plugin/package.xml +++ b/common/tier4_camera_view_rviz_plugin/package.xml @@ -11,7 +11,7 @@ ament_cmake_auto autoware_cmake - autoware_ad_api_specs + autoware_adapi_specs autoware_component_interface_utils geometry_msgs libqt5-core diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index b4324ce05c511..f664f72234f9f 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -12,7 +12,7 @@ ament_cmake_auto autoware_cmake - autoware_ad_api_specs + autoware_adapi_specs autoware_adapi_v1_msgs autoware_adapi_version_msgs autoware_component_interface_specs diff --git a/system/autoware_default_adapi/src/compatibility/autoware_state.hpp b/system/autoware_default_adapi/src/compatibility/autoware_state.hpp index f1270baca50c7..c292f2f62364c 100644 --- a/system/autoware_default_adapi/src/compatibility/autoware_state.hpp +++ b/system/autoware_default_adapi/src/compatibility/autoware_state.hpp @@ -15,9 +15,9 @@ #ifndef COMPATIBILITY__AUTOWARE_STATE_HPP_ #define COMPATIBILITY__AUTOWARE_STATE_HPP_ -#include -#include -#include +#include +#include +#include #include #include @@ -40,14 +40,14 @@ class AutowareStateNode : public rclcpp::Node using ModeChangeAvailable = tier4_system_msgs::msg::ModeChangeAvailable; rclcpp::TimerBase::SharedPtr timer_; // emergency - Sub sub_localization_; - Sub sub_routing_; - Sub sub_operation_mode_; + Sub sub_localization_; + Sub sub_routing_; + Sub sub_operation_mode_; using AutowareState = autoware_system_msgs::msg::AutowareState; - using LocalizationState = autoware::ad_api_specs::localization::InitializationState::Message; - using RoutingState = autoware::ad_api_specs::routing::RouteState::Message; - using OperationModeState = autoware::ad_api_specs::operation_mode::OperationModeState::Message; + using LocalizationState = autoware::adapi_specs::localization::InitializationState::Message; + using RoutingState = autoware::adapi_specs::routing::RouteState::Message; + using OperationModeState = autoware::adapi_specs::operation_mode::OperationModeState::Message; using Trigger = std_srvs::srv::Trigger; std::vector component_states_; std::vector::SharedPtr> sub_component_states_; diff --git a/system/autoware_default_adapi/src/fail_safe.hpp b/system/autoware_default_adapi/src/fail_safe.hpp index 5abeb080c20d7..c5ee08643e802 100644 --- a/system/autoware_default_adapi/src/fail_safe.hpp +++ b/system/autoware_default_adapi/src/fail_safe.hpp @@ -15,7 +15,7 @@ #ifndef FAIL_SAFE_HPP_ #define FAIL_SAFE_HPP_ -#include +#include #include #include #include @@ -32,8 +32,8 @@ class FailSafeNode : public rclcpp::Node explicit FailSafeNode(const rclcpp::NodeOptions & options); private: - using MrmState = autoware::ad_api_specs::fail_safe::MrmState::Message; - Pub pub_mrm_state_; + using MrmState = autoware::adapi_specs::fail_safe::MrmState::Message; + Pub pub_mrm_state_; Sub sub_mrm_state_; MrmState prev_state_; void on_state(const MrmState::ConstSharedPtr msg); diff --git a/system/autoware_default_adapi/src/heartbeat.cpp b/system/autoware_default_adapi/src/heartbeat.cpp index b410624577176..ab3df84904f28 100644 --- a/system/autoware_default_adapi/src/heartbeat.cpp +++ b/system/autoware_default_adapi/src/heartbeat.cpp @@ -23,7 +23,7 @@ HeartbeatNode::HeartbeatNode(const rclcpp::NodeOptions & options) : Node("heartb { // Move this function so that the timer no longer holds it as a reference. const auto on_timer = [this]() { - autoware::ad_api_specs::system::Heartbeat::Message heartbeat; + autoware::adapi_specs::system::Heartbeat::Message heartbeat; heartbeat.stamp = now(); heartbeat.seq = ++sequence_; // Wraps at 65535. pub_->publish(heartbeat); diff --git a/system/autoware_default_adapi/src/heartbeat.hpp b/system/autoware_default_adapi/src/heartbeat.hpp index bf20599a238c6..4647686fe13d5 100644 --- a/system/autoware_default_adapi/src/heartbeat.hpp +++ b/system/autoware_default_adapi/src/heartbeat.hpp @@ -15,7 +15,7 @@ #ifndef HEARTBEAT_HPP_ #define HEARTBEAT_HPP_ -#include +#include #include // This file should be included after messages. @@ -31,7 +31,7 @@ class HeartbeatNode : public rclcpp::Node private: rclcpp::TimerBase::SharedPtr timer_; - Pub pub_; + Pub pub_; uint16_t sequence_ = 0; }; diff --git a/system/autoware_default_adapi/src/interface.hpp b/system/autoware_default_adapi/src/interface.hpp index 5c27a4eb36abe..81ae7aaefc25d 100644 --- a/system/autoware_default_adapi/src/interface.hpp +++ b/system/autoware_default_adapi/src/interface.hpp @@ -15,7 +15,7 @@ #ifndef INTERFACE_HPP_ #define INTERFACE_HPP_ -#include +#include #include // This file should be included after messages. @@ -30,7 +30,7 @@ class InterfaceNode : public rclcpp::Node explicit InterfaceNode(const rclcpp::NodeOptions & options); private: - Srv srv_; + Srv srv_; }; } // namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/src/localization.cpp b/system/autoware_default_adapi/src/localization.cpp index 3b08a44b0987f..779c63224744d 100644 --- a/system/autoware_default_adapi/src/localization.cpp +++ b/system/autoware_default_adapi/src/localization.cpp @@ -30,8 +30,8 @@ LocalizationNode::LocalizationNode(const rclcpp::NodeOptions & options) } void LocalizationNode::on_initialize( - const autoware::ad_api_specs::localization::Initialize::Service::Request::SharedPtr req, - const autoware::ad_api_specs::localization::Initialize::Service::Response::SharedPtr res) + const autoware::adapi_specs::localization::Initialize::Service::Request::SharedPtr req, + const autoware::adapi_specs::localization::Initialize::Service::Response::SharedPtr res) { res->status = localization_conversion::convert_call(cli_initialize_, req); } diff --git a/system/autoware_default_adapi/src/localization.hpp b/system/autoware_default_adapi/src/localization.hpp index 6ecdb7d5cb585..ef4ffd52a6718 100644 --- a/system/autoware_default_adapi/src/localization.hpp +++ b/system/autoware_default_adapi/src/localization.hpp @@ -15,7 +15,7 @@ #ifndef LOCALIZATION_HPP_ #define LOCALIZATION_HPP_ -#include +#include #include #include @@ -32,14 +32,14 @@ class LocalizationNode : public rclcpp::Node private: rclcpp::CallbackGroup::SharedPtr group_cli_; - Srv srv_initialize_; - Pub pub_state_; + Srv srv_initialize_; + Pub pub_state_; Cli cli_initialize_; Sub sub_state_; void on_initialize( - const autoware::ad_api_specs::localization::Initialize::Service::Request::SharedPtr req, - const autoware::ad_api_specs::localization::Initialize::Service::Response::SharedPtr res); + const autoware::adapi_specs::localization::Initialize::Service::Request::SharedPtr req, + const autoware::adapi_specs::localization::Initialize::Service::Response::SharedPtr res); }; } // namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/src/motion.cpp b/system/autoware_default_adapi/src/motion.cpp index 4ca127e62fd8b..dd7d842c3f26f 100644 --- a/system/autoware_default_adapi/src/motion.cpp +++ b/system/autoware_default_adapi/src/motion.cpp @@ -88,7 +88,7 @@ void MotionNode::update_state() void MotionNode::change_state(const State state) { - using MotionState = autoware::ad_api_specs::motion::State::Message; + using MotionState = autoware::adapi_specs::motion::State::Message; static const auto mapping = std::unordered_map( {{State::Unknown, MotionState::UNKNOWN}, {State::Pausing, MotionState::STOPPED}, @@ -149,11 +149,11 @@ void MotionNode::on_is_start_requested( } void MotionNode::on_accept( - const autoware::ad_api_specs::motion::AcceptStart::Service::Request::SharedPtr, - const autoware::ad_api_specs::motion::AcceptStart::Service::Response::SharedPtr res) + const autoware::adapi_specs::motion::AcceptStart::Service::Request::SharedPtr, + const autoware::adapi_specs::motion::AcceptStart::Service::Response::SharedPtr res) { if (state_ != State::Starting) { - using AcceptStartResponse = autoware::ad_api_specs::motion::AcceptStart::Service::Response; + using AcceptStartResponse = autoware::adapi_specs::motion::AcceptStart::Service::Response; throw autoware::component_interface_utils::ServiceException( AcceptStartResponse::ERROR_NOT_STARTING, "The motion state is not starting"); } diff --git a/system/autoware_default_adapi/src/motion.hpp b/system/autoware_default_adapi/src/motion.hpp index fb6a04c992960..ce9cab6eb4bc7 100644 --- a/system/autoware_default_adapi/src/motion.hpp +++ b/system/autoware_default_adapi/src/motion.hpp @@ -15,7 +15,7 @@ #ifndef MOTION_HPP_ #define MOTION_HPP_ -#include +#include #include #include #include @@ -37,8 +37,8 @@ class MotionNode : public rclcpp::Node autoware::motion_utils::VehicleStopChecker vehicle_stop_checker_; rclcpp::TimerBase::SharedPtr timer_; rclcpp::CallbackGroup::SharedPtr group_cli_; - Srv srv_accept_; - Pub pub_state_; + Srv srv_accept_; + Pub pub_state_; Cli cli_set_pause_; Sub sub_is_paused_; Sub sub_is_start_requested_; @@ -63,8 +63,8 @@ class MotionNode : public rclcpp::Node const autoware::component_interface_specs::control::IsStartRequested::Message::ConstSharedPtr msg); void on_accept( - const autoware::ad_api_specs::motion::AcceptStart::Service::Request::SharedPtr req, - const autoware::ad_api_specs::motion::AcceptStart::Service::Response::SharedPtr res); + const autoware::adapi_specs::motion::AcceptStart::Service::Request::SharedPtr req, + const autoware::adapi_specs::motion::AcceptStart::Service::Response::SharedPtr res); }; } // namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/src/operation_mode.hpp b/system/autoware_default_adapi/src/operation_mode.hpp index ddee3daa5d591..fdfe9ce237626 100644 --- a/system/autoware_default_adapi/src/operation_mode.hpp +++ b/system/autoware_default_adapi/src/operation_mode.hpp @@ -15,7 +15,7 @@ #ifndef OPERATION_MODE_HPP_ #define OPERATION_MODE_HPP_ -#include +#include #include #include #include @@ -38,13 +38,13 @@ class OperationModeNode : public rclcpp::Node explicit OperationModeNode(const rclcpp::NodeOptions & options); private: - using OperationModeState = autoware::ad_api_specs::operation_mode::OperationModeState; - using EnableAutowareControl = autoware::ad_api_specs::operation_mode::EnableAutowareControl; - using DisableAutowareControl = autoware::ad_api_specs::operation_mode::DisableAutowareControl; - using ChangeToStop = autoware::ad_api_specs::operation_mode::ChangeToStop; - using ChangeToAutonomous = autoware::ad_api_specs::operation_mode::ChangeToAutonomous; - using ChangeToLocal = autoware::ad_api_specs::operation_mode::ChangeToLocal; - using ChangeToRemote = autoware::ad_api_specs::operation_mode::ChangeToRemote; + using OperationModeState = autoware::adapi_specs::operation_mode::OperationModeState; + using EnableAutowareControl = autoware::adapi_specs::operation_mode::EnableAutowareControl; + using DisableAutowareControl = autoware::adapi_specs::operation_mode::DisableAutowareControl; + using ChangeToStop = autoware::adapi_specs::operation_mode::ChangeToStop; + using ChangeToAutonomous = autoware::adapi_specs::operation_mode::ChangeToAutonomous; + using ChangeToLocal = autoware::adapi_specs::operation_mode::ChangeToLocal; + using ChangeToRemote = autoware::adapi_specs::operation_mode::ChangeToRemote; using OperationModeRequest = autoware::component_interface_specs::system::ChangeOperationMode::Service::Request; using AutowareControlRequest = @@ -57,13 +57,13 @@ class OperationModeNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; rclcpp::TimerBase::SharedPtr timer_; - Pub pub_state_; - Srv srv_stop_mode_; - Srv srv_autonomous_mode_; - Srv srv_local_mode_; - Srv srv_remote_mode_; - Srv srv_enable_control_; - Srv srv_disable_control_; + Pub pub_state_; + Srv srv_stop_mode_; + Srv srv_autonomous_mode_; + Srv srv_local_mode_; + Srv srv_remote_mode_; + Srv srv_enable_control_; + Srv srv_disable_control_; Sub sub_state_; Cli cli_mode_; Cli cli_control_; diff --git a/system/autoware_default_adapi/src/perception.cpp b/system/autoware_default_adapi/src/perception.cpp index 6be0c490e4ad1..e764af4ca816a 100644 --- a/system/autoware_default_adapi/src/perception.cpp +++ b/system/autoware_default_adapi/src/perception.cpp @@ -19,7 +19,7 @@ namespace autoware::default_adapi { -using DynamicObjectArray = autoware::ad_api_specs::perception::DynamicObjectArray; +using DynamicObjectArray = autoware::adapi_specs::perception::DynamicObjectArray; using ObjectClassification = autoware_adapi_v1_msgs::msg::ObjectClassification; using DynamicObject = autoware_adapi_v1_msgs::msg::DynamicObject; using DynamicObjectPath = autoware_adapi_v1_msgs::msg::DynamicObjectPath; diff --git a/system/autoware_default_adapi/src/perception.hpp b/system/autoware_default_adapi/src/perception.hpp index f494d646acdec..61fb2c4667f1d 100644 --- a/system/autoware_default_adapi/src/perception.hpp +++ b/system/autoware_default_adapi/src/perception.hpp @@ -15,7 +15,7 @@ #ifndef PERCEPTION_HPP_ #define PERCEPTION_HPP_ -#include +#include #include #include @@ -40,7 +40,7 @@ class PerceptionNode : public rclcpp::Node explicit PerceptionNode(const rclcpp::NodeOptions & options); private: - Pub pub_object_recognized_; + Pub pub_object_recognized_; Sub sub_object_recognized_; void object_recognize(const autoware::component_interface_specs::perception::ObjectRecognition:: Message::ConstSharedPtr msg); diff --git a/system/autoware_default_adapi/src/planning.hpp b/system/autoware_default_adapi/src/planning.hpp index ca9eb5b2141a2..3a9b99e33a997 100644 --- a/system/autoware_default_adapi/src/planning.hpp +++ b/system/autoware_default_adapi/src/planning.hpp @@ -15,7 +15,7 @@ #ifndef PLANNING_HPP_ #define PLANNING_HPP_ -#include +#include #include #include #include @@ -38,8 +38,8 @@ class PlanningNode : public rclcpp::Node private: using VelocityFactorArray = autoware_adapi_v1_msgs::msg::VelocityFactorArray; using SteeringFactorArray = autoware_adapi_v1_msgs::msg::SteeringFactorArray; - Pub pub_velocity_factors_; - Pub pub_steering_factors_; + Pub pub_velocity_factors_; + Pub pub_steering_factors_; Sub sub_trajectory_; Sub sub_kinematic_state_; std::vector::SharedPtr> sub_velocity_factors_; diff --git a/system/autoware_default_adapi/src/routing.cpp b/system/autoware_default_adapi/src/routing.cpp index 339febb5deb24..4eaa98376b147 100644 --- a/system/autoware_default_adapi/src/routing.cpp +++ b/system/autoware_default_adapi/src/routing.cpp @@ -116,52 +116,52 @@ void RoutingNode::on_route(const Route::Message::ConstSharedPtr msg) } void RoutingNode::on_clear_route( - const autoware::ad_api_specs::routing::ClearRoute::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::ClearRoute::Service::Response::SharedPtr res) + const autoware::adapi_specs::routing::ClearRoute::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::ClearRoute::Service::Response::SharedPtr res) { change_stop_mode(); res->status = conversion::convert_call(cli_clear_route_, req); } void RoutingNode::on_set_route_points( - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Response::SharedPtr res) + const autoware::adapi_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoutePoints::Service::Response::SharedPtr res) { if (state_.state != State::Message::UNSET) { - res->status = route_already_set(); + res->status = route_already_set(); return; } res->status = conversion::convert_call(cli_set_waypoint_route_, req); } void RoutingNode::on_set_route( - const autoware::ad_api_specs::routing::SetRoute::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoute::Service::Response::SharedPtr res) + const autoware::adapi_specs::routing::SetRoute::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoute::Service::Response::SharedPtr res) { if (state_.state != State::Message::UNSET) { - res->status = route_already_set(); + res->status = route_already_set(); return; } res->status = conversion::convert_call(cli_set_lanelet_route_, req); } void RoutingNode::on_change_route_points( - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Response::SharedPtr res) + const autoware::adapi_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoutePoints::Service::Response::SharedPtr res) { if (state_.state != State::Message::SET) { - res->status = route_is_not_set(); + res->status = route_is_not_set(); return; } res->status = conversion::convert_call(cli_set_waypoint_route_, req); } void RoutingNode::on_change_route( - const autoware::ad_api_specs::routing::SetRoute::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoute::Service::Response::SharedPtr res) + const autoware::adapi_specs::routing::SetRoute::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoute::Service::Response::SharedPtr res) { if (state_.state != State::Message::SET) { - res->status = route_is_not_set(); + res->status = route_is_not_set(); return; } res->status = conversion::convert_call(cli_set_lanelet_route_, req); diff --git a/system/autoware_default_adapi/src/routing.hpp b/system/autoware_default_adapi/src/routing.hpp index a78affa27e7c5..10eed606a5f6b 100644 --- a/system/autoware_default_adapi/src/routing.hpp +++ b/system/autoware_default_adapi/src/routing.hpp @@ -15,7 +15,7 @@ #ifndef ROUTING_HPP_ #define ROUTING_HPP_ -#include +#include #include #include #include @@ -38,13 +38,13 @@ class RoutingNode : public rclcpp::Node using Route = autoware::component_interface_specs::planning::LaneletRoute; rclcpp::CallbackGroup::SharedPtr group_cli_; - Pub pub_state_; - Pub pub_route_; - Srv srv_set_route_points_; - Srv srv_set_route_; - Srv srv_change_route_points_; - Srv srv_change_route_; - Srv srv_clear_route_; + Pub pub_state_; + Pub pub_route_; + Srv srv_set_route_points_; + Srv srv_set_route_; + Srv srv_change_route_points_; + Srv srv_change_route_; + Srv srv_clear_route_; Sub sub_state_; Sub sub_route_; Cli cli_set_waypoint_route_; @@ -60,20 +60,20 @@ class RoutingNode : public rclcpp::Node void on_state(const State::Message::ConstSharedPtr msg); void on_route(const Route::Message::ConstSharedPtr msg); void on_clear_route( - const autoware::ad_api_specs::routing::ClearRoute::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::ClearRoute::Service::Response::SharedPtr res); + const autoware::adapi_specs::routing::ClearRoute::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::ClearRoute::Service::Response::SharedPtr res); void on_set_route_points( - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Response::SharedPtr res); + const autoware::adapi_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoutePoints::Service::Response::SharedPtr res); void on_set_route( - const autoware::ad_api_specs::routing::SetRoute::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoute::Service::Response::SharedPtr res); + const autoware::adapi_specs::routing::SetRoute::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoute::Service::Response::SharedPtr res); void on_change_route_points( - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoutePoints::Service::Response::SharedPtr res); + const autoware::adapi_specs::routing::SetRoutePoints::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoutePoints::Service::Response::SharedPtr res); void on_change_route( - const autoware::ad_api_specs::routing::SetRoute::Service::Request::SharedPtr req, - const autoware::ad_api_specs::routing::SetRoute::Service::Response::SharedPtr res); + const autoware::adapi_specs::routing::SetRoute::Service::Request::SharedPtr req, + const autoware::adapi_specs::routing::SetRoute::Service::Response::SharedPtr res); }; } // namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/src/vehicle.cpp b/system/autoware_default_adapi/src/vehicle.cpp index 914d66ec5f95f..5620062ede278 100644 --- a/system/autoware_default_adapi/src/vehicle.cpp +++ b/system/autoware_default_adapi/src/vehicle.cpp @@ -140,7 +140,7 @@ void VehicleNode::publish_kinematics() { if (!kinematic_state_msgs_ || !acceleration_msgs_ || !map_projector_info_) return; - autoware::ad_api_specs::vehicle::VehicleKinematics::Message vehicle_kinematics; + autoware::adapi_specs::vehicle::VehicleKinematics::Message vehicle_kinematics; vehicle_kinematics.pose.header = kinematic_state_msgs_->header; vehicle_kinematics.pose.pose = kinematic_state_msgs_->pose; vehicle_kinematics.twist.header = kinematic_state_msgs_->header; @@ -176,7 +176,7 @@ void VehicleNode::publish_status() !hazard_light_status_msgs_) return; - autoware::ad_api_specs::vehicle::VehicleStatus::Message vehicle_status; + autoware::adapi_specs::vehicle::VehicleStatus::Message vehicle_status; vehicle_status.stamp = now(); vehicle_status.steering_tire_angle = steering_status_msgs_->steering_tire_angle; vehicle_status.gear.status = mapping(gear_type_, gear_status_msgs_->report, ApiGear::UNKNOWN); diff --git a/system/autoware_default_adapi/src/vehicle.hpp b/system/autoware_default_adapi/src/vehicle.hpp index 9c9b6f1b100c6..9bb83cb1613e9 100644 --- a/system/autoware_default_adapi/src/vehicle.hpp +++ b/system/autoware_default_adapi/src/vehicle.hpp @@ -15,7 +15,7 @@ #ifndef VEHICLE_HPP_ #define VEHICLE_HPP_ -#include +#include #include #include #include @@ -40,8 +40,8 @@ class VehicleNode : public rclcpp::Node private: rclcpp::CallbackGroup::SharedPtr group_cli_; - Pub pub_kinematics_; - Pub pub_status_; + Pub pub_kinematics_; + Pub pub_status_; Sub sub_kinematic_state_; Sub sub_acceleration_; Sub sub_steering_; diff --git a/system/autoware_default_adapi/src/vehicle_door.hpp b/system/autoware_default_adapi/src/vehicle_door.hpp index 9629180384eef..50312a38a4cb7 100644 --- a/system/autoware_default_adapi/src/vehicle_door.hpp +++ b/system/autoware_default_adapi/src/vehicle_door.hpp @@ -15,7 +15,7 @@ #ifndef VEHICLE_DOOR_HPP_ #define VEHICLE_DOOR_HPP_ -#include +#include #include #include @@ -36,9 +36,9 @@ class VehicleDoorNode : public rclcpp::Node void on_status( autoware::component_interface_specs::vehicle::DoorStatus::Message::ConstSharedPtr msg); rclcpp::CallbackGroup::SharedPtr group_cli_; - Srv srv_command_; - Srv srv_layout_; - Pub pub_status_; + Srv srv_command_; + Srv srv_layout_; + Pub pub_status_; Cli cli_command_; Cli cli_layout_; Sub sub_status_; diff --git a/system/autoware_default_adapi/src/vehicle_info.hpp b/system/autoware_default_adapi/src/vehicle_info.hpp index bef4f534aa2b9..d7c9ff501eb43 100644 --- a/system/autoware_default_adapi/src/vehicle_info.hpp +++ b/system/autoware_default_adapi/src/vehicle_info.hpp @@ -15,7 +15,7 @@ #ifndef VEHICLE_INFO_HPP_ #define VEHICLE_INFO_HPP_ -#include +#include #include // This file should be included after messages. @@ -30,7 +30,7 @@ class VehicleInfoNode : public rclcpp::Node explicit VehicleInfoNode(const rclcpp::NodeOptions & options); private: - Srv srv_dimensions_; + Srv srv_dimensions_; autoware_adapi_v1_msgs::msg::VehicleDimensions dimensions_; }; diff --git a/system/default_ad_api_helpers/ad_api_adaptors/package.xml b/system/default_ad_api_helpers/ad_api_adaptors/package.xml index 5a6a3199c088a..f6210809122de 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/package.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/package.xml @@ -12,7 +12,7 @@ ament_cmake_auto autoware_cmake - autoware_ad_api_specs + autoware_adapi_specs autoware_adapi_v1_msgs autoware_component_interface_utils autoware_map_height_fitter diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp index 8019dfd765d51..922c4c30b6254 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp @@ -15,7 +15,7 @@ #ifndef INITIAL_POSE_ADAPTOR_HPP_ #define INITIAL_POSE_ADAPTOR_HPP_ -#include +#include #include #include #include @@ -32,7 +32,7 @@ class InitialPoseAdaptor : public rclcpp::Node private: using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; - using Initialize = autoware::ad_api_specs::localization::Initialize; + using Initialize = autoware::adapi_specs::localization::Initialize; rclcpp::Subscription::SharedPtr sub_initial_pose_; autoware::component_interface_utils::Client::SharedPtr cli_initialize_; std::array rviz_particle_covariance_; diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp index c6b3f8b926385..b4577573b665b 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp @@ -15,7 +15,7 @@ #ifndef ROUTING_ADAPTOR_HPP_ #define ROUTING_ADAPTOR_HPP_ -#include +#include #include #include @@ -33,10 +33,10 @@ class RoutingAdaptor : public rclcpp::Node private: using PoseStamped = geometry_msgs::msg::PoseStamped; - using SetRoutePoints = autoware::ad_api_specs::routing::SetRoutePoints; - using ChangeRoutePoints = autoware::ad_api_specs::routing::ChangeRoutePoints; - using ClearRoute = autoware::ad_api_specs::routing::ClearRoute; - using RouteState = autoware::ad_api_specs::routing::RouteState; + using SetRoutePoints = autoware::adapi_specs::routing::SetRoutePoints; + using ChangeRoutePoints = autoware::adapi_specs::routing::ChangeRoutePoints; + using ClearRoute = autoware::adapi_specs::routing::ClearRoute; + using RouteState = autoware::adapi_specs::routing::RouteState; autoware::component_interface_utils::Client::SharedPtr cli_reroute_; autoware::component_interface_utils::Client::SharedPtr cli_route_; autoware::component_interface_utils::Client::SharedPtr cli_clear_; diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml index 649192144d032..0f665cfc4f948 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml +++ b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml @@ -12,7 +12,7 @@ ament_cmake_auto autoware_cmake - autoware_ad_api_specs + autoware_adapi_specs autoware_adapi_v1_msgs autoware_component_interface_utils rclcpp diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp b/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp index ca3a371b9c243..a22a19cc592d2 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp +++ b/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp @@ -15,7 +15,7 @@ #ifndef AUTOMATIC_POSE_INITIALIZER_HPP_ #define AUTOMATIC_POSE_INITIALIZER_HPP_ -#include +#include #include #include @@ -29,8 +29,8 @@ class AutomaticPoseInitializer : public rclcpp::Node private: void on_timer(); - using Initialize = autoware::ad_api_specs::localization::Initialize; - using State = autoware::ad_api_specs::localization::InitializationState; + using Initialize = autoware::adapi_specs::localization::Initialize; + using State = autoware::adapi_specs::localization::InitializationState; rclcpp::CallbackGroup::SharedPtr group_cli_; rclcpp::TimerBase::SharedPtr timer_; autoware::component_interface_utils::Client::SharedPtr cli_initialize_;