From 11dbeefd38e66d65121a0ad59b3cfc3165d349b3 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 22 Oct 2024 00:32:10 +0200 Subject: [PATCH] shorten namespaces Signed-off-by: Esteve Fernandez --- .../component_interface_specs/control.hpp | 4 +- .../localization.hpp | 4 +- .../component_interface_specs/map.hpp | 4 +- .../component_interface_specs/perception.hpp | 4 +- .../component_interface_specs/planning.hpp | 4 +- .../component_interface_specs/system.hpp | 4 +- .../component_interface_specs/vehicle.hpp | 4 +- .../test/test_control.cpp | 6 +-- .../test/test_localization.cpp | 6 +-- .../test/test_map.cpp | 2 +- .../test/test_perception.cpp | 2 +- .../test/test_planning.cpp | 6 +-- .../test/test_system.cpp | 4 +- .../test/test_vehicle.cpp | 10 ++-- .../src/node.hpp | 6 +-- .../src/adapi_pause_interface.hpp | 6 +-- .../src/moderate_stop_interface.hpp | 6 +-- .../predicted_path_checker_node.hpp | 8 ++-- .../predicted_path_checker_node.cpp | 4 +- .../src/geo_pose_projector.hpp | 2 +- .../src/ekf_localization_trigger_module.cpp | 2 +- .../src/gnss_module.cpp | 2 +- .../src/localization_module.cpp | 2 +- .../src/ndt_localization_trigger_module.cpp | 2 +- .../src/pose_initializer_core.hpp | 4 +- .../map_projection_loader.hpp | 2 +- .../map_loader/lanelet2_map_loader_node.hpp | 2 +- .../autoware/gnss_poser/gnss_poser_node.hpp | 2 +- .../autoware_default_adapi/src/fail_safe.hpp | 2 +- .../src/localization.hpp | 4 +- system/autoware_default_adapi/src/motion.cpp | 6 +-- system/autoware_default_adapi/src/motion.hpp | 10 ++-- .../src/operation_mode.hpp | 10 ++-- .../autoware_default_adapi/src/perception.cpp | 2 +- .../autoware_default_adapi/src/perception.hpp | 4 +- .../autoware_default_adapi/src/planning.hpp | 8 ++-- system/autoware_default_adapi/src/routing.cpp | 2 +- system/autoware_default_adapi/src/routing.hpp | 20 ++++---- system/autoware_default_adapi/src/vehicle.cpp | 16 +++---- system/autoware_default_adapi/src/vehicle.hpp | 48 +++++++++---------- .../src/vehicle_door.cpp | 4 +- .../src/vehicle_door.hpp | 10 ++-- 42 files changed, 130 insertions(+), 130 deletions(-) diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp index ead0ae859c14a..03c93d75d674b 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp @@ -23,7 +23,7 @@ #include #include -namespace autoware::component_interface_specs::control_interface +namespace autoware::component_interface_specs::control { struct SetPause @@ -65,6 +65,6 @@ struct IsStopped static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace autoware::component_interface_specs::control_interface +} // namespace autoware::component_interface_specs::control #endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp index b854d4a230731..b2e41a179506a 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp @@ -22,7 +22,7 @@ #include #include -namespace autoware::component_interface_specs::localization_interface +namespace autoware::component_interface_specs::localization { struct Initialize @@ -58,6 +58,6 @@ struct Acceleration static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace autoware::component_interface_specs::localization_interface +} // namespace autoware::component_interface_specs::localization #endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp index 58cea59338b5b..dd1c300a7a2ca 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp @@ -19,7 +19,7 @@ #include -namespace autoware::component_interface_specs::map_interface +namespace autoware::component_interface_specs::map { struct MapProjectorInfo @@ -31,6 +31,6 @@ struct MapProjectorInfo static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace autoware::component_interface_specs::map_interface +} // namespace autoware::component_interface_specs::map #endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp index fe441360d4d44..4f450e6a3ee1c 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp @@ -19,7 +19,7 @@ #include -namespace autoware::component_interface_specs::perception_interface +namespace autoware::component_interface_specs::perception { struct ObjectRecognition @@ -31,6 +31,6 @@ struct ObjectRecognition static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace autoware::component_interface_specs::perception_interface +} // namespace autoware::component_interface_specs::perception #endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp index e4b97bda94d95..247844123881b 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp @@ -24,7 +24,7 @@ #include #include -namespace autoware::component_interface_specs::planning_interface +namespace autoware::component_interface_specs::planning { struct SetLaneletRoute @@ -73,6 +73,6 @@ struct Trajectory static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace autoware::component_interface_specs::planning_interface +} // namespace autoware::component_interface_specs::planning #endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp index 0274142744f2e..6ae3447c0786d 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp @@ -22,7 +22,7 @@ #include #include -namespace autoware::component_interface_specs::system_interface +namespace autoware::component_interface_specs::system { struct MrmState @@ -55,6 +55,6 @@ struct OperationModeState static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace autoware::component_interface_specs::system_interface +} // namespace autoware::component_interface_specs::system #endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp index 13939e5f1b86d..945853d8f532e 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp @@ -26,7 +26,7 @@ #include #include -namespace autoware::component_interface_specs::vehicle_interface +namespace autoware::component_interface_specs::vehicle { struct SteeringStatus @@ -95,6 +95,6 @@ struct DoorStatus static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace autoware::component_interface_specs::vehicle_interface +} // namespace autoware::component_interface_specs::vehicle #endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ diff --git a/common/autoware_component_interface_specs/test/test_control.cpp b/common/autoware_component_interface_specs/test/test_control.cpp index 5db6bfb4c48f2..db6e7817e7a9d 100644 --- a/common/autoware_component_interface_specs/test/test_control.cpp +++ b/common/autoware_component_interface_specs/test/test_control.cpp @@ -18,7 +18,7 @@ TEST(control, interface) { { - using autoware::component_interface_specs::control_interface::IsPaused; + using autoware::component_interface_specs::control::IsPaused; IsPaused is_paused; size_t depth = 1; EXPECT_EQ(is_paused.depth, depth); @@ -27,7 +27,7 @@ TEST(control, interface) } { - using autoware::component_interface_specs::control_interface::IsStartRequested; + using autoware::component_interface_specs::control::IsStartRequested; IsStartRequested is_start_requested; size_t depth = 1; EXPECT_EQ(is_start_requested.depth, depth); @@ -36,7 +36,7 @@ TEST(control, interface) } { - using autoware::component_interface_specs::control_interface::IsStopped; + using autoware::component_interface_specs::control::IsStopped; IsStopped is_stopped; size_t depth = 1; EXPECT_EQ(is_stopped.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_localization.cpp b/common/autoware_component_interface_specs/test/test_localization.cpp index 5d6036e274802..18ec5f15acaf8 100644 --- a/common/autoware_component_interface_specs/test/test_localization.cpp +++ b/common/autoware_component_interface_specs/test/test_localization.cpp @@ -18,7 +18,7 @@ TEST(localization, interface) { { - using autoware::component_interface_specs::localization_interface::InitializationState; + using autoware::component_interface_specs::localization::InitializationState; InitializationState initialization_state; size_t depth = 1; EXPECT_EQ(initialization_state.depth, depth); @@ -27,7 +27,7 @@ TEST(localization, interface) } { - using autoware::component_interface_specs::localization_interface::KinematicState; + using autoware::component_interface_specs::localization::KinematicState; KinematicState kinematic_state; size_t depth = 1; EXPECT_EQ(kinematic_state.depth, depth); @@ -36,7 +36,7 @@ TEST(localization, interface) } { - using autoware::component_interface_specs::localization_interface::Acceleration; + using autoware::component_interface_specs::localization::Acceleration; Acceleration acceleration; size_t depth = 1; EXPECT_EQ(acceleration.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_map.cpp b/common/autoware_component_interface_specs/test/test_map.cpp index ae406cca4e876..aafb33e73c9dc 100644 --- a/common/autoware_component_interface_specs/test/test_map.cpp +++ b/common/autoware_component_interface_specs/test/test_map.cpp @@ -18,7 +18,7 @@ TEST(map, interface) { { - using autoware::component_interface_specs::map_interface::MapProjectorInfo; + using autoware::component_interface_specs::map::MapProjectorInfo; MapProjectorInfo map_projector; size_t depth = 1; EXPECT_EQ(map_projector.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_perception.cpp b/common/autoware_component_interface_specs/test/test_perception.cpp index 5c686e7b64994..8ad6d9dfceb6f 100644 --- a/common/autoware_component_interface_specs/test/test_perception.cpp +++ b/common/autoware_component_interface_specs/test/test_perception.cpp @@ -18,7 +18,7 @@ TEST(perception, interface) { { - using autoware::component_interface_specs::perception_interface::ObjectRecognition; + using autoware::component_interface_specs::perception::ObjectRecognition; ObjectRecognition object_recognition; size_t depth = 1; EXPECT_EQ(object_recognition.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_planning.cpp b/common/autoware_component_interface_specs/test/test_planning.cpp index 9d8bff5a114f4..8278bf86f3861 100644 --- a/common/autoware_component_interface_specs/test/test_planning.cpp +++ b/common/autoware_component_interface_specs/test/test_planning.cpp @@ -18,7 +18,7 @@ TEST(planning, interface) { { - using autoware::component_interface_specs::planning_interface::RouteState; + using autoware::component_interface_specs::planning::RouteState; RouteState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); @@ -27,7 +27,7 @@ TEST(planning, interface) } { - using autoware::component_interface_specs::planning_interface::LaneletRoute; + using autoware::component_interface_specs::planning::LaneletRoute; LaneletRoute route; size_t depth = 1; EXPECT_EQ(route.depth, depth); @@ -36,7 +36,7 @@ TEST(planning, interface) } { - using autoware::component_interface_specs::planning_interface::Trajectory; + using autoware::component_interface_specs::planning::Trajectory; Trajectory trajectory; size_t depth = 1; EXPECT_EQ(trajectory.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_system.cpp b/common/autoware_component_interface_specs/test/test_system.cpp index 19dea82e89bd5..3faff08734905 100644 --- a/common/autoware_component_interface_specs/test/test_system.cpp +++ b/common/autoware_component_interface_specs/test/test_system.cpp @@ -18,7 +18,7 @@ TEST(system, interface) { { - using autoware::component_interface_specs::system_interface::MrmState; + using autoware::component_interface_specs::system::MrmState; MrmState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); @@ -27,7 +27,7 @@ TEST(system, interface) } { - using autoware::component_interface_specs::system_interface::OperationModeState; + using autoware::component_interface_specs::system::OperationModeState; OperationModeState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_vehicle.cpp b/common/autoware_component_interface_specs/test/test_vehicle.cpp index 1b87976571600..e9ee65e2fa210 100644 --- a/common/autoware_component_interface_specs/test/test_vehicle.cpp +++ b/common/autoware_component_interface_specs/test/test_vehicle.cpp @@ -18,7 +18,7 @@ TEST(vehicle, interface) { { - using autoware::component_interface_specs::vehicle_interface::SteeringStatus; + using autoware::component_interface_specs::vehicle::SteeringStatus; SteeringStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -27,7 +27,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle_interface::GearStatus; + using autoware::component_interface_specs::vehicle::GearStatus; GearStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -36,7 +36,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus; + using autoware::component_interface_specs::vehicle::TurnIndicatorStatus; TurnIndicatorStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -45,7 +45,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle_interface::HazardLightStatus; + using autoware::component_interface_specs::vehicle::HazardLightStatus; HazardLightStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -54,7 +54,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle_interface::EnergyStatus; + using autoware::component_interface_specs::vehicle::EnergyStatus; EnergyStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); diff --git a/control/autoware_operation_mode_transition_manager/src/node.hpp b/control/autoware_operation_mode_transition_manager/src/node.hpp index d600bea805656..bbfdeb6a38791 100644 --- a/control/autoware_operation_mode_transition_manager/src/node.hpp +++ b/control/autoware_operation_mode_transition_manager/src/node.hpp @@ -36,11 +36,11 @@ class OperationModeTransitionManager : public rclcpp::Node private: using ChangeAutowareControlAPI = - autoware::component_interface_specs::system_interface::ChangeAutowareControl; + autoware::component_interface_specs::system::ChangeAutowareControl; using ChangeOperationModeAPI = - autoware::component_interface_specs::system_interface::ChangeOperationMode; + autoware::component_interface_specs::system::ChangeOperationMode; using OperationModeStateAPI = - autoware::component_interface_specs::system_interface::OperationModeState; + autoware::component_interface_specs::system::OperationModeState; component_interface_utils::Service::SharedPtr srv_autoware_control_; component_interface_utils::Service::SharedPtr srv_operation_mode_; component_interface_utils::Publisher::SharedPtr pub_operation_mode_; diff --git a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp index c876388963eb6..18e9bcead1b2b 100644 --- a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp @@ -29,9 +29,9 @@ class AdapiPauseInterface private: static constexpr double eps = 1e-3; using Control = autoware_control_msgs::msg::Control; - using SetPause = autoware::component_interface_specs::control_interface::SetPause; - using IsPaused = autoware::component_interface_specs::control_interface::IsPaused; - using IsStartRequested = autoware::component_interface_specs::control_interface::IsStartRequested; + using SetPause = autoware::component_interface_specs::control::SetPause; + using IsPaused = autoware::component_interface_specs::control::IsPaused; + using IsStartRequested = autoware::component_interface_specs::control::IsStartRequested; public: explicit AdapiPauseInterface(rclcpp::Node * node); diff --git a/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp index b29c4a3c6822d..a9ac916d3c10d 100644 --- a/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp @@ -28,9 +28,9 @@ namespace autoware::vehicle_cmd_gate class ModerateStopInterface { private: - using SetStop = autoware::component_interface_specs::control_interface::SetStop; - using IsStopped = autoware::component_interface_specs::control_interface::IsStopped; - using IsStartRequested = autoware::component_interface_specs::control_interface::IsStartRequested; + using SetStop = autoware::component_interface_specs::control::SetStop; + using IsStopped = autoware::component_interface_specs::control::IsStopped; + using IsStartRequested = autoware::component_interface_specs::control::IsStartRequested; public: explicit ModerateStopInterface(rclcpp::Node * node); diff --git a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp index 973c250ff6718..eed39f828873d 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp @@ -97,11 +97,11 @@ class PredictedPathCheckerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_odom_; rclcpp::Subscription::SharedPtr sub_accel_; component_interface_utils::Subscription< - autoware::component_interface_specs::control_interface::IsStopped>::SharedPtr sub_stop_state_; + autoware::component_interface_specs::control::IsStopped>::SharedPtr sub_stop_state_; // Client component_interface_utils::Client< - autoware::component_interface_specs::control_interface::SetStop>::SharedPtr cli_set_stop_; + autoware::component_interface_specs::control::SetStop>::SharedPtr cli_set_stop_; // Data Buffer geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; @@ -110,7 +110,7 @@ class PredictedPathCheckerNode : public rclcpp::Node PredictedObjects::ConstSharedPtr object_ptr_{nullptr}; autoware_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory_; autoware_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory_; - autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr + autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr is_stopped_ptr_{nullptr}; // Core @@ -130,7 +130,7 @@ class PredictedPathCheckerNode : public rclcpp::Node void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg); void onAccel(const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg); void onIsStopped( - const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr + const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr msg); // Timer diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp index 9bd7816566cf3..a84f84ed8edc0 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -132,7 +132,7 @@ void PredictedPathCheckerNode::onAccel( } void PredictedPathCheckerNode::onIsStopped( - const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr + const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr msg) { is_stopped_ptr_ = msg; @@ -417,7 +417,7 @@ void PredictedPathCheckerNode::sendRequest(bool make_stop_vehicle) { if (!is_calling_set_stop_ && cli_set_stop_->service_is_ready()) { const auto req = std::make_shared< - autoware::component_interface_specs::control_interface::SetStop::Service::Request>(); + autoware::component_interface_specs::control::SetStop::Service::Request>(); req->stop = make_stop_vehicle; req->request_source = "predicted_path_checker"; is_calling_set_stop_ = true; diff --git a/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp b/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp index ff9e053ab91b3..493d6cb13246a 100644 --- a/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp +++ b/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp @@ -35,7 +35,7 @@ class GeoPoseProjector : public rclcpp::Node private: using GeoPoseWithCovariance = geographic_msgs::msg::GeoPoseWithCovarianceStamped; using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped; - using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; public: explicit GeoPoseProjector(const rclcpp::NodeOptions & options); diff --git a/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp index ab366dd65afc0..525ebfea4f07d 100644 --- a/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = component_interface_utils::ServiceException; -using Initialize = autoware::component_interface_specs::localization_interface::Initialize; +using Initialize = autoware::component_interface_specs::localization::Initialize; EkfLocalizationTriggerModule::EkfLocalizationTriggerModule(rclcpp::Node * node) : node_(node) { diff --git a/localization/autoware_pose_initializer/src/gnss_module.cpp b/localization/autoware_pose_initializer/src/gnss_module.cpp index 2db89614905be..6d3979f2675ec 100644 --- a/localization/autoware_pose_initializer/src/gnss_module.cpp +++ b/localization/autoware_pose_initializer/src/gnss_module.cpp @@ -37,7 +37,7 @@ void GnssModule::on_pose(PoseWithCovarianceStamped::ConstSharedPtr msg) geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose() { - using Initialize = autoware::component_interface_specs::localization_interface::Initialize; + using Initialize = autoware::component_interface_specs::localization::Initialize; if (!pose_) { throw component_interface_utils::ServiceException( diff --git a/localization/autoware_pose_initializer/src/localization_module.cpp b/localization/autoware_pose_initializer/src/localization_module.cpp index 73b2b556934c9..10345d2a39757 100644 --- a/localization/autoware_pose_initializer/src/localization_module.cpp +++ b/localization/autoware_pose_initializer/src/localization_module.cpp @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = component_interface_utils::ServiceException; -using Initialize = autoware::component_interface_specs::localization_interface::Initialize; +using Initialize = autoware::component_interface_specs::localization::Initialize; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; LocalizationModule::LocalizationModule(rclcpp::Node * node, const std::string & service_name) diff --git a/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp index 757d2450366c6..39cb0f247c27f 100644 --- a/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = component_interface_utils::ServiceException; -using Initialize = autoware::component_interface_specs::localization_interface::Initialize; +using Initialize = autoware::component_interface_specs::localization::Initialize; NdtLocalizationTriggerModule::NdtLocalizationTriggerModule(rclcpp::Node * node) : node_(node) { diff --git a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp index c1adde1dcbb5b..20922e4d46747 100644 --- a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp @@ -42,8 +42,8 @@ class PoseInitializer : public rclcpp::Node private: using ServiceException = component_interface_utils::ServiceException; - using Initialize = autoware::component_interface_specs::localization_interface::Initialize; - using State = autoware::component_interface_specs::localization_interface::InitializationState; + using Initialize = autoware::component_interface_specs::localization::Initialize; + using State = autoware::component_interface_specs::localization::InitializationState; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; rclcpp::CallbackGroup::SharedPtr group_srv_; diff --git a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp index 1bb55cf871df9..7abfd119ae412 100644 --- a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp +++ b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp @@ -34,7 +34,7 @@ class MapProjectionLoader : public rclcpp::Node explicit MapProjectionLoader(const rclcpp::NodeOptions & options); private: - using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; component_interface_utils::Publisher::SharedPtr publisher_; }; } // namespace autoware::map_projection_loader diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index ca1077d336ede..8f182e13ca346 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -44,7 +44,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node const rclcpp::Time & now); private: - using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; void on_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); diff --git a/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp index 2727e2b7dde6f..0f3437a2a8881 100644 --- a/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp +++ b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp @@ -47,7 +47,7 @@ class GNSSPoser : public rclcpp::Node explicit GNSSPoser(const rclcpp::NodeOptions & node_options); private: - using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; void callback_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); void callback_nav_sat_fix(const sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_fix_msg_ptr); diff --git a/system/autoware_default_adapi/src/fail_safe.hpp b/system/autoware_default_adapi/src/fail_safe.hpp index 9e7a77d944523..7b42b97205672 100644 --- a/system/autoware_default_adapi/src/fail_safe.hpp +++ b/system/autoware_default_adapi/src/fail_safe.hpp @@ -34,7 +34,7 @@ class FailSafeNode : public rclcpp::Node private: using MrmState = autoware_ad_api::fail_safe::MrmState::Message; Pub pub_mrm_state_; - Sub sub_mrm_state_; + Sub sub_mrm_state_; MrmState prev_state_; void on_state(const MrmState::ConstSharedPtr msg); }; diff --git a/system/autoware_default_adapi/src/localization.hpp b/system/autoware_default_adapi/src/localization.hpp index 23f83738cf25f..dbbc106621156 100644 --- a/system/autoware_default_adapi/src/localization.hpp +++ b/system/autoware_default_adapi/src/localization.hpp @@ -34,8 +34,8 @@ class LocalizationNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Srv srv_initialize_; Pub pub_state_; - Cli cli_initialize_; - Sub sub_state_; + Cli cli_initialize_; + Sub sub_state_; void on_initialize( const autoware_ad_api::localization::Initialize::Service::Request::SharedPtr req, diff --git a/system/autoware_default_adapi/src/motion.cpp b/system/autoware_default_adapi/src/motion.cpp index 96a3d964c1d0a..32cb1f835bf96 100644 --- a/system/autoware_default_adapi/src/motion.cpp +++ b/system/autoware_default_adapi/src/motion.cpp @@ -122,7 +122,7 @@ void MotionNode::change_pause(bool pause) { if (!is_calling_set_pause_ && cli_set_pause_->service_is_ready()) { const auto req = std::make_shared< - autoware::component_interface_specs::control_interface::SetPause::Service::Request>(); + autoware::component_interface_specs::control::SetPause::Service::Request>(); req->pause = pause; is_calling_set_pause_ = true; cli_set_pause_->async_send_request(req, [this](auto) { is_calling_set_pause_ = false; }); @@ -135,7 +135,7 @@ void MotionNode::on_timer() } void MotionNode::on_is_paused( - const autoware::component_interface_specs::control_interface::IsPaused::Message::ConstSharedPtr + const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr msg) { is_paused_ = msg->data; @@ -143,7 +143,7 @@ void MotionNode::on_is_paused( } void MotionNode::on_is_start_requested( - const autoware::component_interface_specs::control_interface::IsStartRequested::Message:: + const autoware::component_interface_specs::control::IsStartRequested::Message:: ConstSharedPtr msg) { is_start_requested_ = msg->data; diff --git a/system/autoware_default_adapi/src/motion.hpp b/system/autoware_default_adapi/src/motion.hpp index 367f502e38d83..510353fe8da92 100644 --- a/system/autoware_default_adapi/src/motion.hpp +++ b/system/autoware_default_adapi/src/motion.hpp @@ -39,9 +39,9 @@ class MotionNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Srv srv_accept_; Pub pub_state_; - Cli cli_set_pause_; - Sub sub_is_paused_; - Sub + Cli cli_set_pause_; + Sub sub_is_paused_; + Sub sub_is_start_requested_; enum class State { Unknown, Pausing, Paused, Starting, Resuming, Resumed, Moving }; @@ -59,9 +59,9 @@ class MotionNode : public rclcpp::Node void change_pause(bool pause); void on_timer(); void on_is_paused( - const autoware::component_interface_specs::control_interface::IsPaused::Message::ConstSharedPtr + const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr msg); - void on_is_start_requested(const autoware::component_interface_specs::control_interface:: + void on_is_start_requested(const autoware::component_interface_specs::control:: IsStartRequested::Message::ConstSharedPtr msg); void on_accept( const autoware_ad_api::motion::AcceptStart::Service::Request::SharedPtr req, diff --git a/system/autoware_default_adapi/src/operation_mode.hpp b/system/autoware_default_adapi/src/operation_mode.hpp index d6dbc68027229..c76cd5f92cdf0 100644 --- a/system/autoware_default_adapi/src/operation_mode.hpp +++ b/system/autoware_default_adapi/src/operation_mode.hpp @@ -46,9 +46,9 @@ class OperationModeNode : public rclcpp::Node using ChangeToLocal = autoware_ad_api::operation_mode::ChangeToLocal; using ChangeToRemote = autoware_ad_api::operation_mode::ChangeToRemote; using OperationModeRequest = - autoware::component_interface_specs::system_interface::ChangeOperationMode::Service::Request; + autoware::component_interface_specs::system::ChangeOperationMode::Service::Request; using AutowareControlRequest = - autoware::component_interface_specs::system_interface::ChangeAutowareControl::Service::Request; + autoware::component_interface_specs::system::ChangeAutowareControl::Service::Request; using OperationModeAvailability = tier4_system_msgs::msg::OperationModeAvailability; OperationModeState::Message curr_state_; @@ -64,9 +64,9 @@ class OperationModeNode : public rclcpp::Node Srv srv_remote_mode_; Srv srv_enable_control_; Srv srv_disable_control_; - Sub sub_state_; - Cli cli_mode_; - Cli cli_control_; + Sub sub_state_; + Cli cli_mode_; + Cli cli_control_; rclcpp::Subscription::SharedPtr sub_availability_; void on_change_to_stop( diff --git a/system/autoware_default_adapi/src/perception.cpp b/system/autoware_default_adapi/src/perception.cpp index 2e751d4ced2e5..6432746827f20 100644 --- a/system/autoware_default_adapi/src/perception.cpp +++ b/system/autoware_default_adapi/src/perception.cpp @@ -50,7 +50,7 @@ uint8_t PerceptionNode::mapping( } void PerceptionNode::object_recognize( - const autoware::component_interface_specs::perception_interface::ObjectRecognition::Message:: + const autoware::component_interface_specs::perception::ObjectRecognition::Message:: ConstSharedPtr msg) { DynamicObjectArray::Message objects; diff --git a/system/autoware_default_adapi/src/perception.hpp b/system/autoware_default_adapi/src/perception.hpp index 342059571a8b3..2685990082bf9 100644 --- a/system/autoware_default_adapi/src/perception.hpp +++ b/system/autoware_default_adapi/src/perception.hpp @@ -41,9 +41,9 @@ class PerceptionNode : public rclcpp::Node private: Pub pub_object_recognized_; - Sub + Sub sub_object_recognized_; - void object_recognize(const autoware::component_interface_specs::perception_interface:: + void object_recognize(const autoware::component_interface_specs::perception:: ObjectRecognition::Message::ConstSharedPtr msg); uint8_t mapping( std::unordered_map hash_map, uint8_t input, uint8_t default_value); diff --git a/system/autoware_default_adapi/src/planning.hpp b/system/autoware_default_adapi/src/planning.hpp index ae70162a72205..a4e4b0fe0b408 100644 --- a/system/autoware_default_adapi/src/planning.hpp +++ b/system/autoware_default_adapi/src/planning.hpp @@ -40,8 +40,8 @@ class PlanningNode : public rclcpp::Node using SteeringFactorArray = autoware_adapi_v1_msgs::msg::SteeringFactorArray; Pub pub_velocity_factors_; Pub pub_steering_factors_; - Sub sub_trajectory_; - Sub + Sub sub_trajectory_; + Sub sub_kinematic_state_; std::vector::SharedPtr> sub_velocity_factors_; std::vector::SharedPtr> sub_steering_factors_; @@ -50,9 +50,9 @@ class PlanningNode : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_; using VehicleStopChecker = autoware::motion_utils::VehicleStopCheckerBase; - using Trajectory = autoware::component_interface_specs::planning_interface::Trajectory::Message; + using Trajectory = autoware::component_interface_specs::planning::Trajectory::Message; using KinematicState = - autoware::component_interface_specs::localization_interface::KinematicState::Message; + autoware::component_interface_specs::localization::KinematicState::Message; void on_trajectory(const Trajectory::ConstSharedPtr msg); void on_kinematic_state(const KinematicState::ConstSharedPtr msg); void on_timer(); diff --git a/system/autoware_default_adapi/src/routing.cpp b/system/autoware_default_adapi/src/routing.cpp index 460cf73659890..bdb745b0e0dac 100644 --- a/system/autoware_default_adapi/src/routing.cpp +++ b/system/autoware_default_adapi/src/routing.cpp @@ -75,7 +75,7 @@ RoutingNode::RoutingNode(const rclcpp::NodeOptions & options) : Node("routing", void RoutingNode::change_stop_mode() { using OperationModeRequest = - autoware::component_interface_specs::system_interface::ChangeOperationMode::Service::Request; + autoware::component_interface_specs::system::ChangeOperationMode::Service::Request; if (is_auto_mode_) { const auto req = std::make_shared(); req->mode = OperationModeRequest::STOP; diff --git a/system/autoware_default_adapi/src/routing.hpp b/system/autoware_default_adapi/src/routing.hpp index 3eabb4b619904..9de3f312e5b39 100644 --- a/system/autoware_default_adapi/src/routing.hpp +++ b/system/autoware_default_adapi/src/routing.hpp @@ -34,9 +34,9 @@ class RoutingNode : public rclcpp::Node private: using OperationModeState = - autoware::component_interface_specs::system_interface::OperationModeState; - using State = autoware::component_interface_specs::planning_interface::RouteState; - using Route = autoware::component_interface_specs::planning_interface::LaneletRoute; + autoware::component_interface_specs::system::OperationModeState; + using State = autoware::component_interface_specs::planning::RouteState; + using Route = autoware::component_interface_specs::planning::LaneletRoute; rclcpp::CallbackGroup::SharedPtr group_cli_; Pub pub_state_; @@ -46,16 +46,16 @@ class RoutingNode : public rclcpp::Node Srv srv_change_route_points_; Srv srv_change_route_; Srv srv_clear_route_; - Sub sub_state_; - Sub sub_route_; - Cli + Sub sub_state_; + Sub sub_route_; + Cli cli_set_waypoint_route_; - Cli + Cli cli_set_lanelet_route_; - Cli cli_clear_route_; - Cli + Cli cli_clear_route_; + Cli cli_operation_mode_; - Sub + Sub sub_operation_mode_; bool is_auto_mode_; State::Message state_; diff --git a/system/autoware_default_adapi/src/vehicle.cpp b/system/autoware_default_adapi/src/vehicle.cpp index 8542fa1b973c1..bc0a7b9cf8110 100644 --- a/system/autoware_default_adapi/src/vehicle.cpp +++ b/system/autoware_default_adapi/src/vehicle.cpp @@ -24,16 +24,16 @@ namespace autoware::default_adapi { -using GearReport = autoware::component_interface_specs::vehicle_interface::GearStatus::Message; +using GearReport = autoware::component_interface_specs::vehicle::GearStatus::Message; using ApiGear = autoware_adapi_v1_msgs::msg::Gear; using TurnIndicatorsReport = - autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus::Message; + autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message; using ApiTurnIndicator = autoware_adapi_v1_msgs::msg::TurnIndicators; using HazardLightsReport = - autoware::component_interface_specs::vehicle_interface::HazardLightStatus::Message; + autoware::component_interface_specs::vehicle::HazardLightStatus::Message; using ApiHazardLight = autoware_adapi_v1_msgs::msg::HazardLights; using MapProjectorInfo = - autoware::component_interface_specs::map_interface::MapProjectorInfo::Message; + autoware::component_interface_specs::map::MapProjectorInfo::Message; std::unordered_map gear_type_ = { {GearReport::NONE, ApiGear::UNKNOWN}, {GearReport::NEUTRAL, ApiGear::NEUTRAL}, @@ -92,20 +92,20 @@ uint8_t VehicleNode::mapping( } void VehicleNode::kinematic_state( - const autoware::component_interface_specs::localization_interface::KinematicState::Message:: + const autoware::component_interface_specs::localization::KinematicState::Message:: ConstSharedPtr msg_ptr) { kinematic_state_msgs_ = msg_ptr; } void VehicleNode::acceleration_status( - const autoware::component_interface_specs::localization_interface::Acceleration::Message:: + const autoware::component_interface_specs::localization::Acceleration::Message:: ConstSharedPtr msg_ptr) { acceleration_msgs_ = msg_ptr; } -void VehicleNode::steering_status(const autoware::component_interface_specs::vehicle_interface:: +void VehicleNode::steering_status(const autoware::component_interface_specs::vehicle:: SteeringStatus::Message::ConstSharedPtr msg_ptr) { steering_status_msgs_ = msg_ptr; @@ -126,7 +126,7 @@ void VehicleNode::hazard_light_status(const HazardLightsReport::ConstSharedPtr m hazard_light_status_msgs_ = msg_ptr; } -void VehicleNode::energy_status(const autoware::component_interface_specs::vehicle_interface:: +void VehicleNode::energy_status(const autoware::component_interface_specs::vehicle:: EnergyStatus::Message::ConstSharedPtr msg_ptr) { energy_status_msgs_ = msg_ptr; diff --git a/system/autoware_default_adapi/src/vehicle.hpp b/system/autoware_default_adapi/src/vehicle.hpp index fbe6fb5e97aec..873d53a142394 100644 --- a/system/autoware_default_adapi/src/vehicle.hpp +++ b/system/autoware_default_adapi/src/vehicle.hpp @@ -42,50 +42,50 @@ class VehicleNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Pub pub_kinematics_; Pub pub_status_; - Sub + Sub sub_kinematic_state_; - Sub sub_acceleration_; - Sub sub_steering_; - Sub sub_gear_state_; - Sub + Sub sub_acceleration_; + Sub sub_steering_; + Sub sub_gear_state_; + Sub sub_turn_indicator_; - Sub sub_hazard_light_; - Sub sub_energy_level_; - Sub sub_map_projector_info_; + Sub sub_hazard_light_; + Sub sub_energy_level_; + Sub sub_map_projector_info_; rclcpp::TimerBase::SharedPtr timer_; - autoware::component_interface_specs::localization_interface::KinematicState::Message:: + autoware::component_interface_specs::localization::KinematicState::Message:: ConstSharedPtr kinematic_state_msgs_; - autoware::component_interface_specs::localization_interface::Acceleration::Message::ConstSharedPtr + autoware::component_interface_specs::localization::Acceleration::Message::ConstSharedPtr acceleration_msgs_; - autoware::component_interface_specs::vehicle_interface::SteeringStatus::Message::ConstSharedPtr + autoware::component_interface_specs::vehicle::SteeringStatus::Message::ConstSharedPtr steering_status_msgs_; - autoware::component_interface_specs::vehicle_interface::GearStatus::Message::ConstSharedPtr + autoware::component_interface_specs::vehicle::GearStatus::Message::ConstSharedPtr gear_status_msgs_; - autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus::Message:: + autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message:: ConstSharedPtr turn_indicator_status_msgs_; - autoware::component_interface_specs::vehicle_interface::HazardLightStatus::Message::ConstSharedPtr + autoware::component_interface_specs::vehicle::HazardLightStatus::Message::ConstSharedPtr hazard_light_status_msgs_; - autoware::component_interface_specs::vehicle_interface::EnergyStatus::Message::ConstSharedPtr + autoware::component_interface_specs::vehicle::EnergyStatus::Message::ConstSharedPtr energy_status_msgs_; - autoware::component_interface_specs::map_interface::MapProjectorInfo::Message::ConstSharedPtr + autoware::component_interface_specs::map::MapProjectorInfo::Message::ConstSharedPtr map_projector_info_; - void kinematic_state(const autoware::component_interface_specs::localization_interface:: + void kinematic_state(const autoware::component_interface_specs::localization:: KinematicState::Message::ConstSharedPtr msg_ptr); - void acceleration_status(const autoware::component_interface_specs::localization_interface:: + void acceleration_status(const autoware::component_interface_specs::localization:: Acceleration::Message::ConstSharedPtr msg_ptr); - void steering_status(const autoware::component_interface_specs::vehicle_interface:: + void steering_status(const autoware::component_interface_specs::vehicle:: SteeringStatus::Message::ConstSharedPtr msg_ptr); - void gear_status(const autoware::component_interface_specs::vehicle_interface::GearStatus:: + void gear_status(const autoware::component_interface_specs::vehicle::GearStatus:: Message::ConstSharedPtr msg_ptr); - void turn_indicator_status(const autoware::component_interface_specs::vehicle_interface:: + void turn_indicator_status(const autoware::component_interface_specs::vehicle:: TurnIndicatorStatus::Message::ConstSharedPtr msg_ptr); - void map_projector_info(const autoware::component_interface_specs::map_interface:: + void map_projector_info(const autoware::component_interface_specs::map:: MapProjectorInfo::Message::ConstSharedPtr msg_ptr); - void hazard_light_status(const autoware::component_interface_specs::vehicle_interface:: + void hazard_light_status(const autoware::component_interface_specs::vehicle:: HazardLightStatus::Message::ConstSharedPtr msg_ptr); - void energy_status(const autoware::component_interface_specs::vehicle_interface::EnergyStatus:: + void energy_status(const autoware::component_interface_specs::vehicle::EnergyStatus:: Message::ConstSharedPtr msg_ptr); uint8_t mapping( std::unordered_map hash_map, uint8_t input, uint8_t default_value); diff --git a/system/autoware_default_adapi/src/vehicle_door.cpp b/system/autoware_default_adapi/src/vehicle_door.cpp index 091b189c8a058..8c0c63c972de4 100644 --- a/system/autoware_default_adapi/src/vehicle_door.cpp +++ b/system/autoware_default_adapi/src/vehicle_door.cpp @@ -31,12 +31,12 @@ VehicleDoorNode::VehicleDoorNode(const rclcpp::NodeOptions & options) } void VehicleDoorNode::on_status( - autoware::component_interface_specs::vehicle_interface::DoorStatus::Message::ConstSharedPtr msg) + autoware::component_interface_specs::vehicle::DoorStatus::Message::ConstSharedPtr msg) { utils::notify( pub_status_, status_, *msg, utils::ignore_stamp< - autoware::component_interface_specs::vehicle_interface::DoorStatus::Message>); + autoware::component_interface_specs::vehicle::DoorStatus::Message>); } } // namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/src/vehicle_door.hpp b/system/autoware_default_adapi/src/vehicle_door.hpp index f0a461acc86ef..404a65f7ad95f 100644 --- a/system/autoware_default_adapi/src/vehicle_door.hpp +++ b/system/autoware_default_adapi/src/vehicle_door.hpp @@ -34,16 +34,16 @@ class VehicleDoorNode : public rclcpp::Node private: void on_status( - autoware::component_interface_specs::vehicle_interface::DoorStatus::Message::ConstSharedPtr + autoware::component_interface_specs::vehicle::DoorStatus::Message::ConstSharedPtr msg); rclcpp::CallbackGroup::SharedPtr group_cli_; Srv srv_command_; Srv srv_layout_; Pub pub_status_; - Cli cli_command_; - Cli cli_layout_; - Sub sub_status_; - std::optional + Cli cli_command_; + Cli cli_layout_; + Sub sub_status_; + std::optional status_; };