From a7a9e41a45eec90839aae5ba40e7a13781eaf6a6 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <esteve.fernandez@tier4.jp> Date: Wed, 16 Oct 2024 11:10:52 +0200 Subject: [PATCH 1/3] refactor(component_interface_specs): prefix package and namespace with autoware Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp> --- .../CMakeLists.txt | 2 +- .../README.md | 2 +- .../component_interface_specs/control.hpp | 10 +-- .../localization.hpp | 10 +-- .../component_interface_specs/map.hpp | 10 +-- .../component_interface_specs/perception.hpp | 10 +-- .../component_interface_specs/planning.hpp | 10 +-- .../component_interface_specs/system.hpp | 10 +-- .../component_interface_specs/vehicle.hpp | 10 +-- .../package.xml | 4 +- .../test/gtest_main.cpp | 0 .../test/test_control.cpp | 8 +- .../test/test_localization.cpp | 8 +- .../test/test_map.cpp | 4 +- .../test/test_perception.cpp | 4 +- .../test/test_planning.cpp | 8 +- .../test/test_system.cpp | 6 +- .../test/test_vehicle.cpp | 12 +-- .../autoware_test_utils.hpp | 2 +- common/autoware_test_utils/package.xml | 2 +- .../package.xml | 2 +- .../src/node.hpp | 11 ++- control/autoware_vehicle_cmd_gate/package.xml | 2 +- .../src/adapi_pause_interface.hpp | 8 +- .../src/moderate_stop_interface.hpp | 8 +- .../predicted_path_checker_node.hpp | 15 ++-- control/predicted_path_checker/package.xml | 2 +- .../predicted_path_checker_node.cpp | 6 +- .../autoware_geo_pose_projector/package.xml | 2 +- .../src/geo_pose_projector.hpp | 4 +- .../autoware_pose_initializer/package.xml | 2 +- .../src/ekf_localization_trigger_module.cpp | 4 +- .../src/gnss_module.cpp | 4 +- .../src/localization_module.cpp | 4 +- .../src/ndt_localization_trigger_module.cpp | 4 +- .../src/pose_initializer_core.hpp | 6 +- .../map_projection_loader.hpp | 4 +- .../package.xml | 2 +- .../map_loader/lanelet2_map_loader_node.hpp | 4 +- map/map_loader/package.xml | 2 +- .../autoware_planning_test_manager.hpp | 2 +- .../package.xml | 2 +- .../autoware/gnss_poser/gnss_poser_node.hpp | 4 +- sensing/autoware_gnss_poser/package.xml | 2 +- system/autoware_default_adapi/package.xml | 2 +- .../autoware_default_adapi/src/fail_safe.hpp | 4 +- .../src/localization.hpp | 6 +- system/autoware_default_adapi/src/motion.cpp | 10 ++- system/autoware_default_adapi/src/motion.hpp | 17 +++-- .../src/operation_mode.hpp | 14 ++-- .../autoware_default_adapi/src/perception.cpp | 3 +- .../autoware_default_adapi/src/perception.hpp | 8 +- .../autoware_default_adapi/src/planning.hpp | 14 ++-- system/autoware_default_adapi/src/routing.cpp | 3 +- system/autoware_default_adapi/src/routing.hpp | 29 ++++--- system/autoware_default_adapi/src/vehicle.cpp | 25 +++--- system/autoware_default_adapi/src/vehicle.hpp | 76 +++++++++++-------- .../src/vehicle_door.cpp | 7 +- .../src/vehicle_door.hpp | 15 ++-- 59 files changed, 263 insertions(+), 208 deletions(-) rename common/{component_interface_specs => autoware_component_interface_specs}/CMakeLists.txt (90%) rename common/{component_interface_specs => autoware_component_interface_specs}/README.md (61%) rename common/{component_interface_specs/include => autoware_component_interface_specs/include/autoware}/component_interface_specs/control.hpp (87%) rename common/{component_interface_specs/include => autoware_component_interface_specs/include/autoware}/component_interface_specs/localization.hpp (85%) rename common/{component_interface_specs/include => autoware_component_interface_specs/include/autoware}/component_interface_specs/map.hpp (77%) rename common/{component_interface_specs/include => autoware_component_interface_specs/include/autoware}/component_interface_specs/perception.hpp (76%) rename common/{component_interface_specs/include => autoware_component_interface_specs/include/autoware}/component_interface_specs/planning.hpp (89%) rename common/{component_interface_specs/include => autoware_component_interface_specs/include/autoware}/component_interface_specs/system.hpp (86%) rename common/{component_interface_specs/include => autoware_component_interface_specs/include/autoware}/component_interface_specs/vehicle.hpp (91%) rename common/{component_interface_specs => autoware_component_interface_specs}/package.xml (90%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/gtest_main.cpp (100%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/test_control.cpp (83%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/test_localization.cpp (82%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/test_map.cpp (87%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/test_perception.cpp (86%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/test_planning.cpp (82%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/test_system.cpp (83%) rename common/{component_interface_specs => autoware_component_interface_specs}/test/test_vehicle.cpp (79%) diff --git a/common/component_interface_specs/CMakeLists.txt b/common/autoware_component_interface_specs/CMakeLists.txt similarity index 90% rename from common/component_interface_specs/CMakeLists.txt rename to common/autoware_component_interface_specs/CMakeLists.txt index 146f3688513cd..a4e93cc8f04f9 100644 --- a/common/component_interface_specs/CMakeLists.txt +++ b/common/autoware_component_interface_specs/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(component_interface_specs) +project(autoware_component_interface_specs) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/common/component_interface_specs/README.md b/common/autoware_component_interface_specs/README.md similarity index 61% rename from common/component_interface_specs/README.md rename to common/autoware_component_interface_specs/README.md index b9fcd83a29dc0..9d9298a95e329 100644 --- a/common/component_interface_specs/README.md +++ b/common/autoware_component_interface_specs/README.md @@ -1,3 +1,3 @@ -# component_interface_specs +# autoware_component_interface_specs This package is a specification of component interfaces. diff --git a/common/component_interface_specs/include/component_interface_specs/control.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp similarity index 87% rename from common/component_interface_specs/include/component_interface_specs/control.hpp rename to common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp index dfa708dd33403..ead0ae859c14a 100644 --- a/common/component_interface_specs/include/component_interface_specs/control.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ -#define COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ #include <rclcpp/qos.hpp> @@ -23,7 +23,7 @@ #include <tier4_control_msgs/srv/set_pause.hpp> #include <tier4_control_msgs/srv/set_stop.hpp> -namespace control_interface +namespace autoware::component_interface_specs::control_interface { struct SetPause @@ -65,6 +65,6 @@ struct IsStopped static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace control_interface +} // namespace autoware::component_interface_specs::control_interface -#endif // COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/localization.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp similarity index 85% rename from common/component_interface_specs/include/component_interface_specs/localization.hpp rename to common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp index e00d8cef1840d..b854d4a230731 100644 --- a/common/component_interface_specs/include/component_interface_specs/localization.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ -#define COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ #include <rclcpp/qos.hpp> @@ -22,7 +22,7 @@ #include <nav_msgs/msg/odometry.hpp> #include <tier4_localization_msgs/srv/initialize_localization.hpp> -namespace localization_interface +namespace autoware::component_interface_specs::localization_interface { struct Initialize @@ -58,6 +58,6 @@ struct Acceleration static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace localization_interface +} // namespace autoware::component_interface_specs::localization_interface -#endif // COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/map.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp similarity index 77% rename from common/component_interface_specs/include/component_interface_specs/map.hpp rename to common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp index dc162d4a7267a..58cea59338b5b 100644 --- a/common/component_interface_specs/include/component_interface_specs/map.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPONENT_INTERFACE_SPECS__MAP_HPP_ -#define COMPONENT_INTERFACE_SPECS__MAP_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_ #include <rclcpp/qos.hpp> #include <tier4_map_msgs/msg/map_projector_info.hpp> -namespace map_interface +namespace autoware::component_interface_specs::map_interface { struct MapProjectorInfo @@ -31,6 +31,6 @@ struct MapProjectorInfo static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace map_interface +} // namespace autoware::component_interface_specs::map_interface -#endif // COMPONENT_INTERFACE_SPECS__MAP_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/perception.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp similarity index 76% rename from common/component_interface_specs/include/component_interface_specs/perception.hpp rename to common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp index 0c72dbdb12078..fe441360d4d44 100644 --- a/common/component_interface_specs/include/component_interface_specs/perception.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ -#define COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ #include <rclcpp/qos.hpp> #include <autoware_perception_msgs/msg/predicted_objects.hpp> -namespace perception_interface +namespace autoware::component_interface_specs::perception_interface { struct ObjectRecognition @@ -31,6 +31,6 @@ struct ObjectRecognition static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace perception_interface +} // namespace autoware::component_interface_specs::perception_interface -#endif // COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/planning.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp similarity index 89% rename from common/component_interface_specs/include/component_interface_specs/planning.hpp rename to common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp index 58aba53d8ac8a..e4b97bda94d95 100644 --- a/common/component_interface_specs/include/component_interface_specs/planning.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ -#define COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ #include <rclcpp/qos.hpp> @@ -24,7 +24,7 @@ #include <tier4_planning_msgs/srv/set_lanelet_route.hpp> #include <tier4_planning_msgs/srv/set_waypoint_route.hpp> -namespace planning_interface +namespace autoware::component_interface_specs::planning_interface { struct SetLaneletRoute @@ -73,6 +73,6 @@ struct Trajectory static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace planning_interface +} // namespace autoware::component_interface_specs::planning_interface -#endif // COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/system.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp similarity index 86% rename from common/component_interface_specs/include/component_interface_specs/system.hpp rename to common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp index 2132d16dd2969..0274142744f2e 100644 --- a/common/component_interface_specs/include/component_interface_specs/system.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ -#define COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ #include <rclcpp/qos.hpp> @@ -22,7 +22,7 @@ #include <tier4_system_msgs/srv/change_autoware_control.hpp> #include <tier4_system_msgs/srv/change_operation_mode.hpp> -namespace system_interface +namespace autoware::component_interface_specs::system_interface { struct MrmState @@ -55,6 +55,6 @@ struct OperationModeState static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace system_interface +} // namespace autoware::component_interface_specs::system_interface -#endif // COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp similarity index 91% rename from common/component_interface_specs/include/component_interface_specs/vehicle.hpp rename to common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp index e7ce2c5212a25..13939e5f1b86d 100644 --- a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ -#define COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ #include <rclcpp/qos.hpp> @@ -26,7 +26,7 @@ #include <autoware_vehicle_msgs/msg/turn_indicators_report.hpp> #include <tier4_vehicle_msgs/msg/battery_status.hpp> -namespace vehicle_interface +namespace autoware::component_interface_specs::vehicle_interface { struct SteeringStatus @@ -95,6 +95,6 @@ struct DoorStatus static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace vehicle_interface +} // namespace autoware::component_interface_specs::vehicle_interface -#endif // COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ diff --git a/common/component_interface_specs/package.xml b/common/autoware_component_interface_specs/package.xml similarity index 90% rename from common/component_interface_specs/package.xml rename to common/autoware_component_interface_specs/package.xml index fa57bb1641eed..3e53968a94d61 100644 --- a/common/component_interface_specs/package.xml +++ b/common/autoware_component_interface_specs/package.xml @@ -1,9 +1,9 @@ <?xml version="1.0"?> <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> <package format="3"> - <name>component_interface_specs</name> + <name>autoware_component_interface_specs</name> <version>0.0.0</version> - <description>The component_interface_specs package</description> + <description>The autoware_component_interface_specs package</description> <maintainer email="isamu.takagi@tier4.jp">Takagi, Isamu</maintainer> <maintainer email="yukihiro.saito@tier4.jp">Yukihiro Saito</maintainer> <license>Apache License 2.0</license> diff --git a/common/component_interface_specs/test/gtest_main.cpp b/common/autoware_component_interface_specs/test/gtest_main.cpp similarity index 100% rename from common/component_interface_specs/test/gtest_main.cpp rename to common/autoware_component_interface_specs/test/gtest_main.cpp diff --git a/common/component_interface_specs/test/test_control.cpp b/common/autoware_component_interface_specs/test/test_control.cpp similarity index 83% rename from common/component_interface_specs/test/test_control.cpp rename to common/autoware_component_interface_specs/test/test_control.cpp index 366641eacbd23..5db6bfb4c48f2 100644 --- a/common/component_interface_specs/test/test_control.cpp +++ b/common/autoware_component_interface_specs/test/test_control.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "component_interface_specs/control.hpp" +#include "autoware/component_interface_specs/control.hpp" #include "gtest/gtest.h" TEST(control, interface) { { - using control_interface::IsPaused; + using autoware::component_interface_specs::control_interface::IsPaused; IsPaused is_paused; size_t depth = 1; EXPECT_EQ(is_paused.depth, depth); @@ -27,7 +27,7 @@ TEST(control, interface) } { - using control_interface::IsStartRequested; + using autoware::component_interface_specs::control_interface::IsStartRequested; IsStartRequested is_start_requested; size_t depth = 1; EXPECT_EQ(is_start_requested.depth, depth); @@ -36,7 +36,7 @@ TEST(control, interface) } { - using control_interface::IsStopped; + using autoware::component_interface_specs::control_interface::IsStopped; IsStopped is_stopped; size_t depth = 1; EXPECT_EQ(is_stopped.depth, depth); diff --git a/common/component_interface_specs/test/test_localization.cpp b/common/autoware_component_interface_specs/test/test_localization.cpp similarity index 82% rename from common/component_interface_specs/test/test_localization.cpp rename to common/autoware_component_interface_specs/test/test_localization.cpp index 31d8e139bd69a..5d6036e274802 100644 --- a/common/component_interface_specs/test/test_localization.cpp +++ b/common/autoware_component_interface_specs/test/test_localization.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "component_interface_specs/localization.hpp" +#include "autoware/component_interface_specs/localization.hpp" #include "gtest/gtest.h" TEST(localization, interface) { { - using localization_interface::InitializationState; + using autoware::component_interface_specs::localization_interface::InitializationState; InitializationState initialization_state; size_t depth = 1; EXPECT_EQ(initialization_state.depth, depth); @@ -27,7 +27,7 @@ TEST(localization, interface) } { - using localization_interface::KinematicState; + using autoware::component_interface_specs::localization_interface::KinematicState; KinematicState kinematic_state; size_t depth = 1; EXPECT_EQ(kinematic_state.depth, depth); @@ -36,7 +36,7 @@ TEST(localization, interface) } { - using localization_interface::Acceleration; + using autoware::component_interface_specs::localization_interface::Acceleration; Acceleration acceleration; size_t depth = 1; EXPECT_EQ(acceleration.depth, depth); diff --git a/common/component_interface_specs/test/test_map.cpp b/common/autoware_component_interface_specs/test/test_map.cpp similarity index 87% rename from common/component_interface_specs/test/test_map.cpp rename to common/autoware_component_interface_specs/test/test_map.cpp index a65f2cb7120d1..ae406cca4e876 100644 --- a/common/component_interface_specs/test/test_map.cpp +++ b/common/autoware_component_interface_specs/test/test_map.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "component_interface_specs/map.hpp" +#include "autoware/component_interface_specs/map.hpp" #include "gtest/gtest.h" TEST(map, interface) { { - using map_interface::MapProjectorInfo; + using autoware::component_interface_specs::map_interface::MapProjectorInfo; MapProjectorInfo map_projector; size_t depth = 1; EXPECT_EQ(map_projector.depth, depth); diff --git a/common/component_interface_specs/test/test_perception.cpp b/common/autoware_component_interface_specs/test/test_perception.cpp similarity index 86% rename from common/component_interface_specs/test/test_perception.cpp rename to common/autoware_component_interface_specs/test/test_perception.cpp index ec80c06bb119a..5c686e7b64994 100644 --- a/common/component_interface_specs/test/test_perception.cpp +++ b/common/autoware_component_interface_specs/test/test_perception.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "component_interface_specs/perception.hpp" +#include "autoware/component_interface_specs/perception.hpp" #include "gtest/gtest.h" TEST(perception, interface) { { - using perception_interface::ObjectRecognition; + using autoware::component_interface_specs::perception_interface::ObjectRecognition; ObjectRecognition object_recognition; size_t depth = 1; EXPECT_EQ(object_recognition.depth, depth); diff --git a/common/component_interface_specs/test/test_planning.cpp b/common/autoware_component_interface_specs/test/test_planning.cpp similarity index 82% rename from common/component_interface_specs/test/test_planning.cpp rename to common/autoware_component_interface_specs/test/test_planning.cpp index c9cf353de5f34..9d8bff5a114f4 100644 --- a/common/component_interface_specs/test/test_planning.cpp +++ b/common/autoware_component_interface_specs/test/test_planning.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "component_interface_specs/planning.hpp" +#include "autoware/component_interface_specs/planning.hpp" #include "gtest/gtest.h" TEST(planning, interface) { { - using planning_interface::RouteState; + using autoware::component_interface_specs::planning_interface::RouteState; RouteState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); @@ -27,7 +27,7 @@ TEST(planning, interface) } { - using planning_interface::LaneletRoute; + using autoware::component_interface_specs::planning_interface::LaneletRoute; LaneletRoute route; size_t depth = 1; EXPECT_EQ(route.depth, depth); @@ -36,7 +36,7 @@ TEST(planning, interface) } { - using planning_interface::Trajectory; + using autoware::component_interface_specs::planning_interface::Trajectory; Trajectory trajectory; size_t depth = 1; EXPECT_EQ(trajectory.depth, depth); diff --git a/common/component_interface_specs/test/test_system.cpp b/common/autoware_component_interface_specs/test/test_system.cpp similarity index 83% rename from common/component_interface_specs/test/test_system.cpp rename to common/autoware_component_interface_specs/test/test_system.cpp index 416d2effad766..19dea82e89bd5 100644 --- a/common/component_interface_specs/test/test_system.cpp +++ b/common/autoware_component_interface_specs/test/test_system.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "component_interface_specs/system.hpp" +#include "autoware/component_interface_specs/system.hpp" #include "gtest/gtest.h" TEST(system, interface) { { - using system_interface::MrmState; + using autoware::component_interface_specs::system_interface::MrmState; MrmState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); @@ -27,7 +27,7 @@ TEST(system, interface) } { - using system_interface::OperationModeState; + using autoware::component_interface_specs::system_interface::OperationModeState; OperationModeState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); diff --git a/common/component_interface_specs/test/test_vehicle.cpp b/common/autoware_component_interface_specs/test/test_vehicle.cpp similarity index 79% rename from common/component_interface_specs/test/test_vehicle.cpp rename to common/autoware_component_interface_specs/test/test_vehicle.cpp index 1f2041b6cb79e..1b87976571600 100644 --- a/common/component_interface_specs/test/test_vehicle.cpp +++ b/common/autoware_component_interface_specs/test/test_vehicle.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "component_interface_specs/vehicle.hpp" +#include "autoware/component_interface_specs/vehicle.hpp" #include "gtest/gtest.h" TEST(vehicle, interface) { { - using vehicle_interface::SteeringStatus; + using autoware::component_interface_specs::vehicle_interface::SteeringStatus; SteeringStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -27,7 +27,7 @@ TEST(vehicle, interface) } { - using vehicle_interface::GearStatus; + using autoware::component_interface_specs::vehicle_interface::GearStatus; GearStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -36,7 +36,7 @@ TEST(vehicle, interface) } { - using vehicle_interface::TurnIndicatorStatus; + using autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus; TurnIndicatorStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -45,7 +45,7 @@ TEST(vehicle, interface) } { - using vehicle_interface::HazardLightStatus; + using autoware::component_interface_specs::vehicle_interface::HazardLightStatus; HazardLightStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -54,7 +54,7 @@ TEST(vehicle, interface) } { - using vehicle_interface::EnergyStatus; + using autoware::component_interface_specs::vehicle_interface::EnergyStatus; EnergyStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); diff --git a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp index c5c6cdf015e4d..6b00a0dbdd4dc 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp @@ -15,12 +15,12 @@ #ifndef AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_ #define AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_ +#include <autoware/component_interface_specs/planning.hpp> #include <autoware/universe_utils/geometry/geometry.hpp> #include <autoware_lanelet2_extension/io/autoware_osm_parser.hpp> #include <autoware_lanelet2_extension/projection/mgrs_projector.hpp> #include <autoware_lanelet2_extension/utility/message_conversion.hpp> #include <autoware_lanelet2_extension/utility/utilities.hpp> -#include <component_interface_specs/planning.hpp> #include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp> #include <autoware_map_msgs/msg/lanelet_map_bin.hpp> diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index 0a4152404ab44..40edd451f3cab 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -16,6 +16,7 @@ <buildtool_depend>autoware_cmake</buildtool_depend> <depend>ament_index_cpp</depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_control_msgs</depend> <depend>autoware_lanelet2_extension</depend> <depend>autoware_map_msgs</depend> @@ -23,7 +24,6 @@ <depend>autoware_planning_msgs</depend> <depend>autoware_universe_utils</depend> <depend>autoware_vehicle_msgs</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>lanelet2_io</depend> <depend>nav_msgs</depend> diff --git a/control/autoware_operation_mode_transition_manager/package.xml b/control/autoware_operation_mode_transition_manager/package.xml index de514e70a0f2e..ef6c0bc8d252b 100644 --- a/control/autoware_operation_mode_transition_manager/package.xml +++ b/control/autoware_operation_mode_transition_manager/package.xml @@ -12,12 +12,12 @@ <buildtool_depend>autoware_cmake</buildtool_depend> <build_depend>rosidl_default_generators</build_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_control_msgs</depend> <depend>autoware_motion_utils</depend> <depend>autoware_universe_utils</depend> <depend>autoware_vehicle_info_utils</depend> <depend>autoware_vehicle_msgs</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>geometry_msgs</depend> <depend>rclcpp</depend> diff --git a/control/autoware_operation_mode_transition_manager/src/node.hpp b/control/autoware_operation_mode_transition_manager/src/node.hpp index d9b8eaebc4ead..d600bea805656 100644 --- a/control/autoware_operation_mode_transition_manager/src/node.hpp +++ b/control/autoware_operation_mode_transition_manager/src/node.hpp @@ -18,8 +18,8 @@ #include "compatibility.hpp" #include "state.hpp" +#include <autoware/component_interface_specs/system.hpp> #include <autoware/universe_utils/ros/polling_subscriber.hpp> -#include <component_interface_specs/system.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> @@ -35,9 +35,12 @@ class OperationModeTransitionManager : public rclcpp::Node explicit OperationModeTransitionManager(const rclcpp::NodeOptions & options); private: - using ChangeAutowareControlAPI = system_interface::ChangeAutowareControl; - using ChangeOperationModeAPI = system_interface::ChangeOperationMode; - using OperationModeStateAPI = system_interface::OperationModeState; + using ChangeAutowareControlAPI = + autoware::component_interface_specs::system_interface::ChangeAutowareControl; + using ChangeOperationModeAPI = + autoware::component_interface_specs::system_interface::ChangeOperationMode; + using OperationModeStateAPI = + autoware::component_interface_specs::system_interface::OperationModeState; component_interface_utils::Service<ChangeAutowareControlAPI>::SharedPtr srv_autoware_control_; component_interface_utils::Service<ChangeOperationModeAPI>::SharedPtr srv_operation_mode_; component_interface_utils::Publisher<OperationModeStateAPI>::SharedPtr pub_operation_mode_; diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml index 60bbf23f9d5a8..532553da103e9 100644 --- a/control/autoware_vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -16,12 +16,12 @@ <build_depend>rosidl_default_generators</build_depend> <depend>autoware_adapi_v1_msgs</depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_control_msgs</depend> <depend>autoware_motion_utils</depend> <depend>autoware_universe_utils</depend> <depend>autoware_vehicle_info_utils</depend> <depend>autoware_vehicle_msgs</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>diagnostic_updater</depend> <depend>geometry_msgs</depend> 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 6f3aa70bcea54..c876388963eb6 100644 --- a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp @@ -15,7 +15,7 @@ #ifndef ADAPI_PAUSE_INTERFACE_HPP_ #define ADAPI_PAUSE_INTERFACE_HPP_ -#include <component_interface_specs/control.hpp> +#include <autoware/component_interface_specs/control.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> @@ -29,9 +29,9 @@ class AdapiPauseInterface private: static constexpr double eps = 1e-3; using Control = autoware_control_msgs::msg::Control; - using SetPause = control_interface::SetPause; - using IsPaused = control_interface::IsPaused; - using IsStartRequested = control_interface::IsStartRequested; + 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; 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 012e75d0c207e..b29c4a3c6822d 100644 --- a/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp @@ -15,7 +15,7 @@ #ifndef MODERATE_STOP_INTERFACE_HPP_ #define MODERATE_STOP_INTERFACE_HPP_ -#include <component_interface_specs/control.hpp> +#include <autoware/component_interface_specs/control.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> @@ -28,9 +28,9 @@ namespace autoware::vehicle_cmd_gate class ModerateStopInterface { private: - using SetStop = control_interface::SetStop; - using IsStopped = control_interface::IsStopped; - using IsStartRequested = control_interface::IsStartRequested; + 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; 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 b3afcded60438..973c250ff6718 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 @@ -15,13 +15,13 @@ #ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ #define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ +#include <autoware/component_interface_specs/control.hpp> #include <autoware/motion_utils/trajectory/conversion.hpp> #include <autoware/motion_utils/trajectory/trajectory.hpp> #include <autoware/universe_utils/geometry/geometry.hpp> #include <autoware/universe_utils/ros/self_pose_listener.hpp> #include <autoware_vehicle_info_utils/vehicle_info.hpp> #include <autoware_vehicle_info_utils/vehicle_info_utils.hpp> -#include <component_interface_specs/control.hpp> #include <component_interface_utils/rclcpp.hpp> #include <diagnostic_updater/diagnostic_updater.hpp> #include <predicted_path_checker/collision_checker.hpp> @@ -96,10 +96,12 @@ class PredictedPathCheckerNode : public rclcpp::Node sub_predicted_trajectory_; rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_; rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr sub_accel_; - component_interface_utils::Subscription<control_interface::IsStopped>::SharedPtr sub_stop_state_; + component_interface_utils::Subscription< + autoware::component_interface_specs::control_interface::IsStopped>::SharedPtr sub_stop_state_; // Client - component_interface_utils::Client<control_interface::SetStop>::SharedPtr cli_set_stop_; + component_interface_utils::Client< + autoware::component_interface_specs::control_interface::SetStop>::SharedPtr cli_set_stop_; // Data Buffer geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; @@ -108,7 +110,8 @@ 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_; - control_interface::IsStopped::Message::ConstSharedPtr is_stopped_ptr_{nullptr}; + autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr + is_stopped_ptr_{nullptr}; // Core std::unique_ptr<CollisionChecker> collision_checker_; @@ -126,7 +129,9 @@ class PredictedPathCheckerNode : public rclcpp::Node void onPredictedTrajectory(const autoware_planning_msgs::msg::Trajectory::SharedPtr msg); void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg); void onAccel(const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg); - void onIsStopped(const control_interface::IsStopped::Message::ConstSharedPtr msg); + void onIsStopped( + const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr + msg); // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml index 153d11107a8cb..6bceb24c4439d 100644 --- a/control/predicted_path_checker/package.xml +++ b/control/predicted_path_checker/package.xml @@ -12,13 +12,13 @@ <buildtool_depend>ament_cmake</buildtool_depend> <buildtool_depend>autoware_cmake</buildtool_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_motion_utils</depend> <depend>autoware_perception_msgs</depend> <depend>autoware_planning_msgs</depend> <depend>autoware_universe_utils</depend> <depend>autoware_vehicle_info_utils</depend> <depend>boost</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>diagnostic_updater</depend> <depend>eigen</depend> 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 d8cf5c34bf535..9bd7816566cf3 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,8 @@ void PredictedPathCheckerNode::onAccel( } void PredictedPathCheckerNode::onIsStopped( - const control_interface::IsStopped::Message::ConstSharedPtr msg) + const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr + msg) { is_stopped_ptr_ = msg; @@ -415,7 +416,8 @@ void PredictedPathCheckerNode::checkVehicleState(diagnostic_updater::DiagnosticS void PredictedPathCheckerNode::sendRequest(bool make_stop_vehicle) { if (!is_calling_set_stop_ && cli_set_stop_->service_is_ready()) { - const auto req = std::make_shared<control_interface::SetStop::Service::Request>(); + const auto req = std::make_shared< + autoware::component_interface_specs::control_interface::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/package.xml b/localization/autoware_geo_pose_projector/package.xml index 2d7c09f9e2ce2..4f02d4ff40981 100644 --- a/localization/autoware_geo_pose_projector/package.xml +++ b/localization/autoware_geo_pose_projector/package.xml @@ -17,8 +17,8 @@ <buildtool_depend>ament_cmake_auto</buildtool_depend> <buildtool_depend>autoware_cmake</buildtool_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_geography_utils</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>geographic_msgs</depend> <depend>geometry_msgs</depend> 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 3ece595a7b1bd..ff9e053ab91b3 100644 --- a/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp +++ b/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp @@ -15,7 +15,7 @@ #ifndef GEO_POSE_PROJECTOR_HPP_ #define GEO_POSE_PROJECTOR_HPP_ -#include <component_interface_specs/map.hpp> +#include <autoware/component_interface_specs/map.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.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 = map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo; public: explicit GeoPoseProjector(const rclcpp::NodeOptions & options); diff --git a/localization/autoware_pose_initializer/package.xml b/localization/autoware_pose_initializer/package.xml index d1ffc4ca4aef5..83a961a322c6a 100644 --- a/localization/autoware_pose_initializer/package.xml +++ b/localization/autoware_pose_initializer/package.xml @@ -19,11 +19,11 @@ <buildtool_depend>ament_cmake</buildtool_depend> <buildtool_depend>autoware_cmake</buildtool_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_localization_util</depend> <depend>autoware_map_height_fitter</depend> <depend>autoware_motion_utils</depend> <depend>autoware_universe_utils</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>geometry_msgs</depend> <depend>rclcpp</depend> 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 630635da870b0..ab366dd65afc0 100644 --- a/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp @@ -14,7 +14,7 @@ #include "ekf_localization_trigger_module.hpp" -#include <component_interface_specs/localization.hpp> +#include <autoware/component_interface_specs/localization.hpp> #include <component_interface_utils/rclcpp/exceptions.hpp> #include <memory> @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = component_interface_utils::ServiceException; -using Initialize = localization_interface::Initialize; +using Initialize = autoware::component_interface_specs::localization_interface::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 c5fd1490b271e..2db89614905be 100644 --- a/localization/autoware_pose_initializer/src/gnss_module.cpp +++ b/localization/autoware_pose_initializer/src/gnss_module.cpp @@ -14,7 +14,7 @@ #include "gnss_module.hpp" -#include <component_interface_specs/localization.hpp> +#include <autoware/component_interface_specs/localization.hpp> #include <component_interface_utils/rclcpp/exceptions.hpp> #include <memory> @@ -37,7 +37,7 @@ void GnssModule::on_pose(PoseWithCovarianceStamped::ConstSharedPtr msg) geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose() { - using Initialize = localization_interface::Initialize; + using Initialize = autoware::component_interface_specs::localization_interface::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 0b2a63a55447b..73b2b556934c9 100644 --- a/localization/autoware_pose_initializer/src/localization_module.cpp +++ b/localization/autoware_pose_initializer/src/localization_module.cpp @@ -14,7 +14,7 @@ #include "localization_module.hpp" -#include <component_interface_specs/localization.hpp> +#include <autoware/component_interface_specs/localization.hpp> #include <component_interface_utils/rclcpp/exceptions.hpp> #include <memory> @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = component_interface_utils::ServiceException; -using Initialize = localization_interface::Initialize; +using Initialize = autoware::component_interface_specs::localization_interface::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 5acf0909d21cf..757d2450366c6 100644 --- a/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp @@ -14,7 +14,7 @@ #include "ndt_localization_trigger_module.hpp" -#include <component_interface_specs/localization.hpp> +#include <autoware/component_interface_specs/localization.hpp> #include <component_interface_utils/rclcpp/exceptions.hpp> #include <memory> @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = component_interface_utils::ServiceException; -using Initialize = localization_interface::Initialize; +using Initialize = autoware::component_interface_specs::localization_interface::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 b9a6a66590b78..c1adde1dcbb5b 100644 --- a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp @@ -17,8 +17,8 @@ #include "autoware/localization_util/diagnostics_module.hpp" +#include <autoware/component_interface_specs/localization.hpp> #include <autoware/universe_utils/ros/logger_level_configure.hpp> -#include <component_interface_specs/localization.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> @@ -42,8 +42,8 @@ class PoseInitializer : public rclcpp::Node private: using ServiceException = component_interface_utils::ServiceException; - using Initialize = localization_interface::Initialize; - using State = localization_interface::InitializationState; + using Initialize = autoware::component_interface_specs::localization_interface::Initialize; + using State = autoware::component_interface_specs::localization_interface::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 feb7483f37811..1bb55cf871df9 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 @@ -17,7 +17,7 @@ #include "rclcpp/rclcpp.hpp" -#include <component_interface_specs/map.hpp> +#include <autoware/component_interface_specs/map.hpp> #include <component_interface_utils/rclcpp.hpp> #include <string> @@ -34,7 +34,7 @@ class MapProjectionLoader : public rclcpp::Node explicit MapProjectionLoader(const rclcpp::NodeOptions & options); private: - using MapProjectorInfo = map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo; component_interface_utils::Publisher<MapProjectorInfo>::SharedPtr publisher_; }; } // namespace autoware::map_projection_loader diff --git a/map/autoware_map_projection_loader/package.xml b/map/autoware_map_projection_loader/package.xml index ca25cbf728d26..d58d4191300a3 100644 --- a/map/autoware_map_projection_loader/package.xml +++ b/map/autoware_map_projection_loader/package.xml @@ -16,8 +16,8 @@ <buildtool_depend>ament_cmake_auto</buildtool_depend> <buildtool_depend>autoware_cmake</buildtool_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_lanelet2_extension</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>rclcpp</depend> <depend>rclcpp_components</depend> 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 e38d65201ee56..ca1077d336ede 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 @@ -15,8 +15,8 @@ #ifndef MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ #define MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ +#include <autoware/component_interface_specs/map.hpp> #include <autoware_lanelet2_extension/version.hpp> -#include <component_interface_specs/map.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> @@ -44,7 +44,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node const rclcpp::Time & now); private: - using MapProjectorInfo = map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map_interface::MapProjectorInfo; void on_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index b8f92504a8b99..6ab72f3d5f95b 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -19,10 +19,10 @@ <buildtool_depend>ament_cmake_auto</buildtool_depend> <buildtool_depend>autoware_cmake</buildtool_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_geography_utils</depend> <depend>autoware_lanelet2_extension</depend> <depend>autoware_map_msgs</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>fmt</depend> <depend>geometry_msgs</depend> diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp index 52c60a612d1bd..f26f9c8eb6dde 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp @@ -30,7 +30,7 @@ << std::endl; \ } -#include <component_interface_specs/planning.hpp> +#include <autoware/component_interface_specs/planning.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index f2aa5513ee81a..898c78391fb72 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -13,6 +13,7 @@ <buildtool_depend>ament_cmake_auto</buildtool_depend> <buildtool_depend>autoware_cmake</buildtool_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_control_msgs</depend> <depend>autoware_lanelet2_extension</depend> <depend>autoware_map_msgs</depend> @@ -23,7 +24,6 @@ <depend>autoware_test_utils</depend> <depend>autoware_universe_utils</depend> <depend>autoware_vehicle_msgs</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>lanelet2_io</depend> <depend>nav_msgs</depend> 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 e551aedab8cf5..2727e2b7dde6f 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 @@ -14,7 +14,7 @@ #ifndef AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ #define AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ -#include <component_interface_specs/map.hpp> +#include <autoware/component_interface_specs/map.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> @@ -47,7 +47,7 @@ class GNSSPoser : public rclcpp::Node explicit GNSSPoser(const rclcpp::NodeOptions & node_options); private: - using MapProjectorInfo = map_interface::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs::map_interface::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/sensing/autoware_gnss_poser/package.xml b/sensing/autoware_gnss_poser/package.xml index 7d7fb27777fed..6565148df73cd 100644 --- a/sensing/autoware_gnss_poser/package.xml +++ b/sensing/autoware_gnss_poser/package.xml @@ -19,9 +19,9 @@ <build_depend>libboost-dev</build_depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_geography_utils</depend> <depend>autoware_sensing_msgs</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>geographic_msgs</depend> <depend>geographiclib</depend> diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index 5c6e10a73fa9c..4c9664912db40 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -15,13 +15,13 @@ <depend>autoware_ad_api_specs</depend> <depend>autoware_adapi_v1_msgs</depend> <depend>autoware_adapi_version_msgs</depend> + <depend>autoware_component_interface_specs</depend> <depend>autoware_geography_utils</depend> <depend>autoware_motion_utils</depend> <depend>autoware_planning_msgs</depend> <depend>autoware_system_msgs</depend> <depend>autoware_vehicle_info_utils</depend> <depend>autoware_vehicle_msgs</depend> - <depend>component_interface_specs</depend> <depend>component_interface_utils</depend> <depend>diagnostic_graph_utils</depend> <depend>geographic_msgs</depend> diff --git a/system/autoware_default_adapi/src/fail_safe.hpp b/system/autoware_default_adapi/src/fail_safe.hpp index 268fc6d4d95e4..9e7a77d944523 100644 --- a/system/autoware_default_adapi/src/fail_safe.hpp +++ b/system/autoware_default_adapi/src/fail_safe.hpp @@ -15,8 +15,8 @@ #ifndef FAIL_SAFE_HPP_ #define FAIL_SAFE_HPP_ +#include <autoware/component_interface_specs/system.hpp> #include <autoware_ad_api_specs/fail_safe.hpp> -#include <component_interface_specs/system.hpp> #include <component_interface_utils/rclcpp.hpp> #include <rclcpp/rclcpp.hpp> @@ -34,7 +34,7 @@ class FailSafeNode : public rclcpp::Node private: using MrmState = autoware_ad_api::fail_safe::MrmState::Message; Pub<autoware_ad_api::fail_safe::MrmState> pub_mrm_state_; - Sub<system_interface::MrmState> sub_mrm_state_; + Sub<autoware::component_interface_specs::system_interface::MrmState> 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 d9104f393f712..23f83738cf25f 100644 --- a/system/autoware_default_adapi/src/localization.hpp +++ b/system/autoware_default_adapi/src/localization.hpp @@ -15,8 +15,8 @@ #ifndef LOCALIZATION_HPP_ #define LOCALIZATION_HPP_ +#include <autoware/component_interface_specs/localization.hpp> #include <autoware_ad_api_specs/localization.hpp> -#include <component_interface_specs/localization.hpp> #include <rclcpp/rclcpp.hpp> // This file should be included after messages. @@ -34,8 +34,8 @@ class LocalizationNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Srv<autoware_ad_api::localization::Initialize> srv_initialize_; Pub<autoware_ad_api::localization::InitializationState> pub_state_; - Cli<localization_interface::Initialize> cli_initialize_; - Sub<localization_interface::InitializationState> sub_state_; + Cli<autoware::component_interface_specs::localization_interface::Initialize> cli_initialize_; + Sub<autoware::component_interface_specs::localization_interface::InitializationState> 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 87d4df371abb7..96a3d964c1d0a 100644 --- a/system/autoware_default_adapi/src/motion.cpp +++ b/system/autoware_default_adapi/src/motion.cpp @@ -121,7 +121,8 @@ void MotionNode::update_pause(const State state) void MotionNode::change_pause(bool pause) { if (!is_calling_set_pause_ && cli_set_pause_->service_is_ready()) { - const auto req = std::make_shared<control_interface::SetPause::Service::Request>(); + const auto req = std::make_shared< + autoware::component_interface_specs::control_interface::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; }); @@ -133,14 +134,17 @@ void MotionNode::on_timer() update_state(); } -void MotionNode::on_is_paused(const control_interface::IsPaused::Message::ConstSharedPtr msg) +void MotionNode::on_is_paused( + const autoware::component_interface_specs::control_interface::IsPaused::Message::ConstSharedPtr + msg) { is_paused_ = msg->data; update_state(); } void MotionNode::on_is_start_requested( - const control_interface::IsStartRequested::Message::ConstSharedPtr msg) + const autoware::component_interface_specs::control_interface::IsStartRequested::Message:: + ConstSharedPtr msg) { is_start_requested_ = msg->data; update_state(); diff --git a/system/autoware_default_adapi/src/motion.hpp b/system/autoware_default_adapi/src/motion.hpp index 043eb6568e141..367f502e38d83 100644 --- a/system/autoware_default_adapi/src/motion.hpp +++ b/system/autoware_default_adapi/src/motion.hpp @@ -15,9 +15,9 @@ #ifndef MOTION_HPP_ #define MOTION_HPP_ +#include <autoware/component_interface_specs/control.hpp> #include <autoware/motion_utils/vehicle/vehicle_state_checker.hpp> #include <autoware_ad_api_specs/motion.hpp> -#include <component_interface_specs/control.hpp> #include <component_interface_utils/rclcpp.hpp> #include <component_interface_utils/status.hpp> #include <rclcpp/rclcpp.hpp> @@ -39,9 +39,10 @@ class MotionNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Srv<autoware_ad_api::motion::AcceptStart> srv_accept_; Pub<autoware_ad_api::motion::State> pub_state_; - Cli<control_interface::SetPause> cli_set_pause_; - Sub<control_interface::IsPaused> sub_is_paused_; - Sub<control_interface::IsStartRequested> sub_is_start_requested_; + Cli<autoware::component_interface_specs::control_interface::SetPause> cli_set_pause_; + Sub<autoware::component_interface_specs::control_interface::IsPaused> sub_is_paused_; + Sub<autoware::component_interface_specs::control_interface::IsStartRequested> + sub_is_start_requested_; enum class State { Unknown, Pausing, Paused, Starting, Resuming, Resumed, Moving }; State state_; @@ -57,9 +58,11 @@ class MotionNode : public rclcpp::Node void update_pause(const State state); void change_pause(bool pause); void on_timer(); - void on_is_paused(const control_interface::IsPaused::Message::ConstSharedPtr msg); - void on_is_start_requested( - const control_interface::IsStartRequested::Message::ConstSharedPtr msg); + void on_is_paused( + const autoware::component_interface_specs::control_interface::IsPaused::Message::ConstSharedPtr + msg); + void on_is_start_requested(const autoware::component_interface_specs::control_interface:: + IsStartRequested::Message::ConstSharedPtr msg); void on_accept( const autoware_ad_api::motion::AcceptStart::Service::Request::SharedPtr req, const autoware_ad_api::motion::AcceptStart::Service::Response::SharedPtr res); diff --git a/system/autoware_default_adapi/src/operation_mode.hpp b/system/autoware_default_adapi/src/operation_mode.hpp index 3b139ad875b8d..d6dbc68027229 100644 --- a/system/autoware_default_adapi/src/operation_mode.hpp +++ b/system/autoware_default_adapi/src/operation_mode.hpp @@ -15,8 +15,8 @@ #ifndef OPERATION_MODE_HPP_ #define OPERATION_MODE_HPP_ +#include <autoware/component_interface_specs/system.hpp> #include <autoware_ad_api_specs/operation_mode.hpp> -#include <component_interface_specs/system.hpp> #include <component_interface_utils/status.hpp> #include <rclcpp/rclcpp.hpp> @@ -45,8 +45,10 @@ class OperationModeNode : public rclcpp::Node using ChangeToAutonomous = autoware_ad_api::operation_mode::ChangeToAutonomous; using ChangeToLocal = autoware_ad_api::operation_mode::ChangeToLocal; using ChangeToRemote = autoware_ad_api::operation_mode::ChangeToRemote; - using OperationModeRequest = system_interface::ChangeOperationMode::Service::Request; - using AutowareControlRequest = system_interface::ChangeAutowareControl::Service::Request; + using OperationModeRequest = + autoware::component_interface_specs::system_interface::ChangeOperationMode::Service::Request; + using AutowareControlRequest = + autoware::component_interface_specs::system_interface::ChangeAutowareControl::Service::Request; using OperationModeAvailability = tier4_system_msgs::msg::OperationModeAvailability; OperationModeState::Message curr_state_; @@ -62,9 +64,9 @@ class OperationModeNode : public rclcpp::Node Srv<autoware_ad_api::operation_mode::ChangeToRemote> srv_remote_mode_; Srv<autoware_ad_api::operation_mode::EnableAutowareControl> srv_enable_control_; Srv<autoware_ad_api::operation_mode::DisableAutowareControl> srv_disable_control_; - Sub<system_interface::OperationModeState> sub_state_; - Cli<system_interface::ChangeOperationMode> cli_mode_; - Cli<system_interface::ChangeAutowareControl> cli_control_; + Sub<autoware::component_interface_specs::system_interface::OperationModeState> sub_state_; + Cli<autoware::component_interface_specs::system_interface::ChangeOperationMode> cli_mode_; + Cli<autoware::component_interface_specs::system_interface::ChangeAutowareControl> cli_control_; rclcpp::Subscription<OperationModeAvailability>::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 c92bac2f5f139..2e751d4ced2e5 100644 --- a/system/autoware_default_adapi/src/perception.cpp +++ b/system/autoware_default_adapi/src/perception.cpp @@ -50,7 +50,8 @@ uint8_t PerceptionNode::mapping( } void PerceptionNode::object_recognize( - const perception_interface::ObjectRecognition::Message::ConstSharedPtr msg) + const autoware::component_interface_specs::perception_interface::ObjectRecognition::Message:: + ConstSharedPtr msg) { DynamicObjectArray::Message objects; objects.header = msg->header; diff --git a/system/autoware_default_adapi/src/perception.hpp b/system/autoware_default_adapi/src/perception.hpp index 4eb83c57293ba..342059571a8b3 100644 --- a/system/autoware_default_adapi/src/perception.hpp +++ b/system/autoware_default_adapi/src/perception.hpp @@ -15,8 +15,8 @@ #ifndef PERCEPTION_HPP_ #define PERCEPTION_HPP_ +#include <autoware/component_interface_specs/perception.hpp> #include <autoware_ad_api_specs/perception.hpp> -#include <component_interface_specs/perception.hpp> #include <rclcpp/rclcpp.hpp> #include <autoware_adapi_v1_msgs/msg/dynamic_object.hpp> @@ -41,8 +41,10 @@ class PerceptionNode : public rclcpp::Node private: Pub<autoware_ad_api::perception::DynamicObjectArray> pub_object_recognized_; - Sub<perception_interface::ObjectRecognition> sub_object_recognized_; - void object_recognize(const perception_interface::ObjectRecognition::Message::ConstSharedPtr msg); + Sub<autoware::component_interface_specs::perception_interface::ObjectRecognition> + sub_object_recognized_; + void object_recognize(const autoware::component_interface_specs::perception_interface:: + ObjectRecognition::Message::ConstSharedPtr msg); uint8_t mapping( std::unordered_map<uint8_t, uint8_t> 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 f67de9f7b9221..ae70162a72205 100644 --- a/system/autoware_default_adapi/src/planning.hpp +++ b/system/autoware_default_adapi/src/planning.hpp @@ -15,10 +15,10 @@ #ifndef PLANNING_HPP_ #define PLANNING_HPP_ +#include <autoware/component_interface_specs/localization.hpp> +#include <autoware/component_interface_specs/planning.hpp> #include <autoware/motion_utils/vehicle/vehicle_state_checker.hpp> #include <autoware_ad_api_specs/planning.hpp> -#include <component_interface_specs/localization.hpp> -#include <component_interface_specs/planning.hpp> #include <rclcpp/rclcpp.hpp> #include <memory> @@ -40,8 +40,9 @@ class PlanningNode : public rclcpp::Node using SteeringFactorArray = autoware_adapi_v1_msgs::msg::SteeringFactorArray; Pub<autoware_ad_api::planning::VelocityFactors> pub_velocity_factors_; Pub<autoware_ad_api::planning::SteeringFactors> pub_steering_factors_; - Sub<planning_interface::Trajectory> sub_trajectory_; - Sub<localization_interface::KinematicState> sub_kinematic_state_; + Sub<autoware::component_interface_specs::planning_interface::Trajectory> sub_trajectory_; + Sub<autoware::component_interface_specs::localization_interface::KinematicState> + sub_kinematic_state_; std::vector<rclcpp::Subscription<VelocityFactorArray>::SharedPtr> sub_velocity_factors_; std::vector<rclcpp::Subscription<SteeringFactorArray>::SharedPtr> sub_steering_factors_; std::vector<VelocityFactorArray::ConstSharedPtr> velocity_factors_; @@ -49,8 +50,9 @@ class PlanningNode : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_; using VehicleStopChecker = autoware::motion_utils::VehicleStopCheckerBase; - using Trajectory = planning_interface::Trajectory::Message; - using KinematicState = localization_interface::KinematicState::Message; + using Trajectory = autoware::component_interface_specs::planning_interface::Trajectory::Message; + using KinematicState = + autoware::component_interface_specs::localization_interface::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 767cfc37d3f25..460cf73659890 100644 --- a/system/autoware_default_adapi/src/routing.cpp +++ b/system/autoware_default_adapi/src/routing.cpp @@ -74,7 +74,8 @@ RoutingNode::RoutingNode(const rclcpp::NodeOptions & options) : Node("routing", void RoutingNode::change_stop_mode() { - using OperationModeRequest = system_interface::ChangeOperationMode::Service::Request; + using OperationModeRequest = + autoware::component_interface_specs::system_interface::ChangeOperationMode::Service::Request; if (is_auto_mode_) { const auto req = std::make_shared<OperationModeRequest>(); req->mode = OperationModeRequest::STOP; diff --git a/system/autoware_default_adapi/src/routing.hpp b/system/autoware_default_adapi/src/routing.hpp index 9033373c3a064..3eabb4b619904 100644 --- a/system/autoware_default_adapi/src/routing.hpp +++ b/system/autoware_default_adapi/src/routing.hpp @@ -15,9 +15,9 @@ #ifndef ROUTING_HPP_ #define ROUTING_HPP_ +#include <autoware/component_interface_specs/planning.hpp> +#include <autoware/component_interface_specs/system.hpp> #include <autoware_ad_api_specs/routing.hpp> -#include <component_interface_specs/planning.hpp> -#include <component_interface_specs/system.hpp> #include <component_interface_utils/status.hpp> #include <rclcpp/rclcpp.hpp> @@ -33,9 +33,10 @@ class RoutingNode : public rclcpp::Node explicit RoutingNode(const rclcpp::NodeOptions & options); private: - using OperationModeState = system_interface::OperationModeState; - using State = planning_interface::RouteState; - using Route = planning_interface::LaneletRoute; + 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; rclcpp::CallbackGroup::SharedPtr group_cli_; Pub<autoware_ad_api::routing::RouteState> pub_state_; @@ -45,13 +46,17 @@ class RoutingNode : public rclcpp::Node Srv<autoware_ad_api::routing::ChangeRoutePoints> srv_change_route_points_; Srv<autoware_ad_api::routing::ChangeRoute> srv_change_route_; Srv<autoware_ad_api::routing::ClearRoute> srv_clear_route_; - Sub<planning_interface::RouteState> sub_state_; - Sub<planning_interface::LaneletRoute> sub_route_; - Cli<planning_interface::SetWaypointRoute> cli_set_waypoint_route_; - Cli<planning_interface::SetLaneletRoute> cli_set_lanelet_route_; - Cli<planning_interface::ClearRoute> cli_clear_route_; - Cli<system_interface::ChangeOperationMode> cli_operation_mode_; - Sub<system_interface::OperationModeState> sub_operation_mode_; + Sub<autoware::component_interface_specs::planning_interface::RouteState> sub_state_; + Sub<autoware::component_interface_specs::planning_interface::LaneletRoute> sub_route_; + Cli<autoware::component_interface_specs::planning_interface::SetWaypointRoute> + cli_set_waypoint_route_; + Cli<autoware::component_interface_specs::planning_interface::SetLaneletRoute> + cli_set_lanelet_route_; + Cli<autoware::component_interface_specs::planning_interface::ClearRoute> cli_clear_route_; + Cli<autoware::component_interface_specs::system_interface::ChangeOperationMode> + cli_operation_mode_; + Sub<autoware::component_interface_specs::system_interface::OperationModeState> + 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 5421f382795ef..8542fa1b973c1 100644 --- a/system/autoware_default_adapi/src/vehicle.cpp +++ b/system/autoware_default_adapi/src/vehicle.cpp @@ -24,13 +24,16 @@ namespace autoware::default_adapi { -using GearReport = vehicle_interface::GearStatus::Message; +using GearReport = autoware::component_interface_specs::vehicle_interface::GearStatus::Message; using ApiGear = autoware_adapi_v1_msgs::msg::Gear; -using TurnIndicatorsReport = vehicle_interface::TurnIndicatorStatus::Message; +using TurnIndicatorsReport = + autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus::Message; using ApiTurnIndicator = autoware_adapi_v1_msgs::msg::TurnIndicators; -using HazardLightsReport = vehicle_interface::HazardLightStatus::Message; +using HazardLightsReport = + autoware::component_interface_specs::vehicle_interface::HazardLightStatus::Message; using ApiHazardLight = autoware_adapi_v1_msgs::msg::HazardLights; -using MapProjectorInfo = map_interface::MapProjectorInfo::Message; +using MapProjectorInfo = + autoware::component_interface_specs::map_interface::MapProjectorInfo::Message; std::unordered_map<uint8_t, uint8_t> gear_type_ = { {GearReport::NONE, ApiGear::UNKNOWN}, {GearReport::NEUTRAL, ApiGear::NEUTRAL}, @@ -89,19 +92,21 @@ uint8_t VehicleNode::mapping( } void VehicleNode::kinematic_state( - const localization_interface::KinematicState::Message::ConstSharedPtr msg_ptr) + const autoware::component_interface_specs::localization_interface::KinematicState::Message:: + ConstSharedPtr msg_ptr) { kinematic_state_msgs_ = msg_ptr; } void VehicleNode::acceleration_status( - const localization_interface::Acceleration::Message::ConstSharedPtr msg_ptr) + const autoware::component_interface_specs::localization_interface::Acceleration::Message:: + ConstSharedPtr msg_ptr) { acceleration_msgs_ = msg_ptr; } -void VehicleNode::steering_status( - const vehicle_interface::SteeringStatus::Message::ConstSharedPtr msg_ptr) +void VehicleNode::steering_status(const autoware::component_interface_specs::vehicle_interface:: + SteeringStatus::Message::ConstSharedPtr msg_ptr) { steering_status_msgs_ = msg_ptr; } @@ -121,8 +126,8 @@ void VehicleNode::hazard_light_status(const HazardLightsReport::ConstSharedPtr m hazard_light_status_msgs_ = msg_ptr; } -void VehicleNode::energy_status( - const vehicle_interface::EnergyStatus::Message::ConstSharedPtr msg_ptr) +void VehicleNode::energy_status(const autoware::component_interface_specs::vehicle_interface:: + 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 5e3818340b819..fbe6fb5e97aec 100644 --- a/system/autoware_default_adapi/src/vehicle.hpp +++ b/system/autoware_default_adapi/src/vehicle.hpp @@ -15,10 +15,10 @@ #ifndef VEHICLE_HPP_ #define VEHICLE_HPP_ +#include <autoware/component_interface_specs/localization.hpp> +#include <autoware/component_interface_specs/map.hpp> +#include <autoware/component_interface_specs/vehicle.hpp> #include <autoware_ad_api_specs/vehicle.hpp> -#include <component_interface_specs/localization.hpp> -#include <component_interface_specs/map.hpp> -#include <component_interface_specs/vehicle.hpp> #include <rclcpp/rclcpp.hpp> #include <autoware_adapi_v1_msgs/msg/gear.hpp> @@ -42,37 +42,51 @@ class VehicleNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Pub<autoware_ad_api::vehicle::VehicleKinematics> pub_kinematics_; Pub<autoware_ad_api::vehicle::VehicleStatus> pub_status_; - Sub<localization_interface::KinematicState> sub_kinematic_state_; - Sub<localization_interface::Acceleration> sub_acceleration_; - Sub<vehicle_interface::SteeringStatus> sub_steering_; - Sub<vehicle_interface::GearStatus> sub_gear_state_; - Sub<vehicle_interface::TurnIndicatorStatus> sub_turn_indicator_; - Sub<vehicle_interface::HazardLightStatus> sub_hazard_light_; - Sub<vehicle_interface::EnergyStatus> sub_energy_level_; - Sub<map_interface::MapProjectorInfo> sub_map_projector_info_; + Sub<autoware::component_interface_specs::localization_interface::KinematicState> + sub_kinematic_state_; + Sub<autoware::component_interface_specs::localization_interface::Acceleration> sub_acceleration_; + Sub<autoware::component_interface_specs::vehicle_interface::SteeringStatus> sub_steering_; + Sub<autoware::component_interface_specs::vehicle_interface::GearStatus> sub_gear_state_; + Sub<autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus> + sub_turn_indicator_; + Sub<autoware::component_interface_specs::vehicle_interface::HazardLightStatus> sub_hazard_light_; + Sub<autoware::component_interface_specs::vehicle_interface::EnergyStatus> sub_energy_level_; + Sub<autoware::component_interface_specs::map_interface::MapProjectorInfo> sub_map_projector_info_; rclcpp::TimerBase::SharedPtr timer_; - localization_interface::KinematicState::Message::ConstSharedPtr kinematic_state_msgs_; - localization_interface::Acceleration::Message::ConstSharedPtr acceleration_msgs_; - vehicle_interface::SteeringStatus::Message::ConstSharedPtr steering_status_msgs_; - vehicle_interface::GearStatus::Message::ConstSharedPtr gear_status_msgs_; - vehicle_interface::TurnIndicatorStatus::Message::ConstSharedPtr turn_indicator_status_msgs_; - vehicle_interface::HazardLightStatus::Message::ConstSharedPtr hazard_light_status_msgs_; - vehicle_interface::EnergyStatus::Message::ConstSharedPtr energy_status_msgs_; - map_interface::MapProjectorInfo::Message::ConstSharedPtr map_projector_info_; + autoware::component_interface_specs::localization_interface::KinematicState::Message:: + ConstSharedPtr kinematic_state_msgs_; + autoware::component_interface_specs::localization_interface::Acceleration::Message::ConstSharedPtr + acceleration_msgs_; + autoware::component_interface_specs::vehicle_interface::SteeringStatus::Message::ConstSharedPtr + steering_status_msgs_; + autoware::component_interface_specs::vehicle_interface::GearStatus::Message::ConstSharedPtr + gear_status_msgs_; + autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus::Message:: + ConstSharedPtr turn_indicator_status_msgs_; + autoware::component_interface_specs::vehicle_interface::HazardLightStatus::Message::ConstSharedPtr + hazard_light_status_msgs_; + autoware::component_interface_specs::vehicle_interface::EnergyStatus::Message::ConstSharedPtr + energy_status_msgs_; + autoware::component_interface_specs::map_interface::MapProjectorInfo::Message::ConstSharedPtr + map_projector_info_; - void kinematic_state( - const localization_interface::KinematicState::Message::ConstSharedPtr msg_ptr); - void acceleration_status( - const localization_interface::Acceleration::Message::ConstSharedPtr msg_ptr); - void steering_status(const vehicle_interface::SteeringStatus::Message::ConstSharedPtr msg_ptr); - void gear_status(const vehicle_interface::GearStatus::Message::ConstSharedPtr msg_ptr); - void turn_indicator_status( - const vehicle_interface::TurnIndicatorStatus::Message::ConstSharedPtr msg_ptr); - void map_projector_info(const map_interface::MapProjectorInfo::Message::ConstSharedPtr msg_ptr); - void hazard_light_status( - const vehicle_interface::HazardLightStatus::Message::ConstSharedPtr msg_ptr); - void energy_status(const vehicle_interface::EnergyStatus::Message::ConstSharedPtr msg_ptr); + void kinematic_state(const autoware::component_interface_specs::localization_interface:: + KinematicState::Message::ConstSharedPtr msg_ptr); + void acceleration_status(const autoware::component_interface_specs::localization_interface:: + Acceleration::Message::ConstSharedPtr msg_ptr); + void steering_status(const autoware::component_interface_specs::vehicle_interface:: + SteeringStatus::Message::ConstSharedPtr msg_ptr); + void gear_status(const autoware::component_interface_specs::vehicle_interface::GearStatus:: + Message::ConstSharedPtr msg_ptr); + void turn_indicator_status(const autoware::component_interface_specs::vehicle_interface:: + TurnIndicatorStatus::Message::ConstSharedPtr msg_ptr); + void map_projector_info(const autoware::component_interface_specs::map_interface:: + MapProjectorInfo::Message::ConstSharedPtr msg_ptr); + void hazard_light_status(const autoware::component_interface_specs::vehicle_interface:: + HazardLightStatus::Message::ConstSharedPtr msg_ptr); + void energy_status(const autoware::component_interface_specs::vehicle_interface::EnergyStatus:: + Message::ConstSharedPtr msg_ptr); uint8_t mapping( std::unordered_map<uint8_t, uint8_t> hash_map, uint8_t input, uint8_t default_value); void publish_kinematics(); diff --git a/system/autoware_default_adapi/src/vehicle_door.cpp b/system/autoware_default_adapi/src/vehicle_door.cpp index e897bc37eff42..091b189c8a058 100644 --- a/system/autoware_default_adapi/src/vehicle_door.cpp +++ b/system/autoware_default_adapi/src/vehicle_door.cpp @@ -30,10 +30,13 @@ VehicleDoorNode::VehicleDoorNode(const rclcpp::NodeOptions & options) adaptor.init_sub(sub_status_, this, &VehicleDoorNode::on_status); } -void VehicleDoorNode::on_status(vehicle_interface::DoorStatus::Message::ConstSharedPtr msg) +void VehicleDoorNode::on_status( + autoware::component_interface_specs::vehicle_interface::DoorStatus::Message::ConstSharedPtr msg) { utils::notify( - pub_status_, status_, *msg, utils::ignore_stamp<vehicle_interface::DoorStatus::Message>); + pub_status_, status_, *msg, + utils::ignore_stamp< + autoware::component_interface_specs::vehicle_interface::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 8f6c2da83247d..f0a461acc86ef 100644 --- a/system/autoware_default_adapi/src/vehicle_door.hpp +++ b/system/autoware_default_adapi/src/vehicle_door.hpp @@ -15,8 +15,8 @@ #ifndef VEHICLE_DOOR_HPP_ #define VEHICLE_DOOR_HPP_ +#include <autoware/component_interface_specs/vehicle.hpp> #include <autoware_ad_api_specs/vehicle.hpp> -#include <component_interface_specs/vehicle.hpp> #include <rclcpp/rclcpp.hpp> #include <optional> @@ -33,15 +33,18 @@ class VehicleDoorNode : public rclcpp::Node explicit VehicleDoorNode(const rclcpp::NodeOptions & options); private: - void on_status(vehicle_interface::DoorStatus::Message::ConstSharedPtr msg); + void on_status( + autoware::component_interface_specs::vehicle_interface::DoorStatus::Message::ConstSharedPtr + msg); rclcpp::CallbackGroup::SharedPtr group_cli_; Srv<autoware_ad_api::vehicle::DoorCommand> srv_command_; Srv<autoware_ad_api::vehicle::DoorLayout> srv_layout_; Pub<autoware_ad_api::vehicle::DoorStatus> pub_status_; - Cli<vehicle_interface::DoorCommand> cli_command_; - Cli<vehicle_interface::DoorLayout> cli_layout_; - Sub<vehicle_interface::DoorStatus> sub_status_; - std::optional<vehicle_interface::DoorStatus::Message> status_; + Cli<autoware::component_interface_specs::vehicle_interface::DoorCommand> cli_command_; + Cli<autoware::component_interface_specs::vehicle_interface::DoorLayout> cli_layout_; + Sub<autoware::component_interface_specs::vehicle_interface::DoorStatus> sub_status_; + std::optional<autoware::component_interface_specs::vehicle_interface::DoorStatus::Message> + status_; }; } // namespace autoware::default_adapi From d3fc4a9046ac75331dc3b81076f2b43053108c0f Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <esteve.fernandez@tier4.jp> Date: Tue, 22 Oct 2024 00:32:10 +0200 Subject: [PATCH 2/3] shorten namespaces Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp> --- .../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 <tier4_control_msgs/srv/set_pause.hpp> #include <tier4_control_msgs/srv/set_stop.hpp> -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 <nav_msgs/msg/odometry.hpp> #include <tier4_localization_msgs/srv/initialize_localization.hpp> -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 <tier4_map_msgs/msg/map_projector_info.hpp> -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 <autoware_perception_msgs/msg/predicted_objects.hpp> -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 <tier4_planning_msgs/srv/set_lanelet_route.hpp> #include <tier4_planning_msgs/srv/set_waypoint_route.hpp> -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 <tier4_system_msgs/srv/change_autoware_control.hpp> #include <tier4_system_msgs/srv/change_operation_mode.hpp> -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 <autoware_vehicle_msgs/msg/turn_indicators_report.hpp> #include <tier4_vehicle_msgs/msg/battery_status.hpp> -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<ChangeAutowareControlAPI>::SharedPtr srv_autoware_control_; component_interface_utils::Service<ChangeOperationModeAPI>::SharedPtr srv_operation_mode_; component_interface_utils::Publisher<OperationModeStateAPI>::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<nav_msgs::msg::Odometry>::SharedPtr sub_odom_; rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::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<MapProjectorInfo>::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<autoware_ad_api::fail_safe::MrmState> pub_mrm_state_; - Sub<autoware::component_interface_specs::system_interface::MrmState> sub_mrm_state_; + Sub<autoware::component_interface_specs::system::MrmState> 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<autoware_ad_api::localization::Initialize> srv_initialize_; Pub<autoware_ad_api::localization::InitializationState> pub_state_; - Cli<autoware::component_interface_specs::localization_interface::Initialize> cli_initialize_; - Sub<autoware::component_interface_specs::localization_interface::InitializationState> sub_state_; + Cli<autoware::component_interface_specs::localization::Initialize> cli_initialize_; + Sub<autoware::component_interface_specs::localization::InitializationState> 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<autoware_ad_api::motion::AcceptStart> srv_accept_; Pub<autoware_ad_api::motion::State> pub_state_; - Cli<autoware::component_interface_specs::control_interface::SetPause> cli_set_pause_; - Sub<autoware::component_interface_specs::control_interface::IsPaused> sub_is_paused_; - Sub<autoware::component_interface_specs::control_interface::IsStartRequested> + Cli<autoware::component_interface_specs::control::SetPause> cli_set_pause_; + Sub<autoware::component_interface_specs::control::IsPaused> sub_is_paused_; + Sub<autoware::component_interface_specs::control::IsStartRequested> 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<autoware_ad_api::operation_mode::ChangeToRemote> srv_remote_mode_; Srv<autoware_ad_api::operation_mode::EnableAutowareControl> srv_enable_control_; Srv<autoware_ad_api::operation_mode::DisableAutowareControl> srv_disable_control_; - Sub<autoware::component_interface_specs::system_interface::OperationModeState> sub_state_; - Cli<autoware::component_interface_specs::system_interface::ChangeOperationMode> cli_mode_; - Cli<autoware::component_interface_specs::system_interface::ChangeAutowareControl> cli_control_; + Sub<autoware::component_interface_specs::system::OperationModeState> sub_state_; + Cli<autoware::component_interface_specs::system::ChangeOperationMode> cli_mode_; + Cli<autoware::component_interface_specs::system::ChangeAutowareControl> cli_control_; rclcpp::Subscription<OperationModeAvailability>::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<autoware_ad_api::perception::DynamicObjectArray> pub_object_recognized_; - Sub<autoware::component_interface_specs::perception_interface::ObjectRecognition> + Sub<autoware::component_interface_specs::perception::ObjectRecognition> 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<uint8_t, uint8_t> 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<autoware_ad_api::planning::VelocityFactors> pub_velocity_factors_; Pub<autoware_ad_api::planning::SteeringFactors> pub_steering_factors_; - Sub<autoware::component_interface_specs::planning_interface::Trajectory> sub_trajectory_; - Sub<autoware::component_interface_specs::localization_interface::KinematicState> + Sub<autoware::component_interface_specs::planning::Trajectory> sub_trajectory_; + Sub<autoware::component_interface_specs::localization::KinematicState> sub_kinematic_state_; std::vector<rclcpp::Subscription<VelocityFactorArray>::SharedPtr> sub_velocity_factors_; std::vector<rclcpp::Subscription<SteeringFactorArray>::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<OperationModeRequest>(); 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<autoware_ad_api::routing::RouteState> pub_state_; @@ -46,16 +46,16 @@ class RoutingNode : public rclcpp::Node Srv<autoware_ad_api::routing::ChangeRoutePoints> srv_change_route_points_; Srv<autoware_ad_api::routing::ChangeRoute> srv_change_route_; Srv<autoware_ad_api::routing::ClearRoute> srv_clear_route_; - Sub<autoware::component_interface_specs::planning_interface::RouteState> sub_state_; - Sub<autoware::component_interface_specs::planning_interface::LaneletRoute> sub_route_; - Cli<autoware::component_interface_specs::planning_interface::SetWaypointRoute> + Sub<autoware::component_interface_specs::planning::RouteState> sub_state_; + Sub<autoware::component_interface_specs::planning::LaneletRoute> sub_route_; + Cli<autoware::component_interface_specs::planning::SetWaypointRoute> cli_set_waypoint_route_; - Cli<autoware::component_interface_specs::planning_interface::SetLaneletRoute> + Cli<autoware::component_interface_specs::planning::SetLaneletRoute> cli_set_lanelet_route_; - Cli<autoware::component_interface_specs::planning_interface::ClearRoute> cli_clear_route_; - Cli<autoware::component_interface_specs::system_interface::ChangeOperationMode> + Cli<autoware::component_interface_specs::planning::ClearRoute> cli_clear_route_; + Cli<autoware::component_interface_specs::system::ChangeOperationMode> cli_operation_mode_; - Sub<autoware::component_interface_specs::system_interface::OperationModeState> + Sub<autoware::component_interface_specs::system::OperationModeState> 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<uint8_t, uint8_t> 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<autoware_ad_api::vehicle::VehicleKinematics> pub_kinematics_; Pub<autoware_ad_api::vehicle::VehicleStatus> pub_status_; - Sub<autoware::component_interface_specs::localization_interface::KinematicState> + Sub<autoware::component_interface_specs::localization::KinematicState> sub_kinematic_state_; - Sub<autoware::component_interface_specs::localization_interface::Acceleration> sub_acceleration_; - Sub<autoware::component_interface_specs::vehicle_interface::SteeringStatus> sub_steering_; - Sub<autoware::component_interface_specs::vehicle_interface::GearStatus> sub_gear_state_; - Sub<autoware::component_interface_specs::vehicle_interface::TurnIndicatorStatus> + Sub<autoware::component_interface_specs::localization::Acceleration> sub_acceleration_; + Sub<autoware::component_interface_specs::vehicle::SteeringStatus> sub_steering_; + Sub<autoware::component_interface_specs::vehicle::GearStatus> sub_gear_state_; + Sub<autoware::component_interface_specs::vehicle::TurnIndicatorStatus> sub_turn_indicator_; - Sub<autoware::component_interface_specs::vehicle_interface::HazardLightStatus> sub_hazard_light_; - Sub<autoware::component_interface_specs::vehicle_interface::EnergyStatus> sub_energy_level_; - Sub<autoware::component_interface_specs::map_interface::MapProjectorInfo> sub_map_projector_info_; + Sub<autoware::component_interface_specs::vehicle::HazardLightStatus> sub_hazard_light_; + Sub<autoware::component_interface_specs::vehicle::EnergyStatus> sub_energy_level_; + Sub<autoware::component_interface_specs::map::MapProjectorInfo> 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<uint8_t, uint8_t> 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<autoware_ad_api::vehicle::DoorCommand> srv_command_; Srv<autoware_ad_api::vehicle::DoorLayout> srv_layout_; Pub<autoware_ad_api::vehicle::DoorStatus> pub_status_; - Cli<autoware::component_interface_specs::vehicle_interface::DoorCommand> cli_command_; - Cli<autoware::component_interface_specs::vehicle_interface::DoorLayout> cli_layout_; - Sub<autoware::component_interface_specs::vehicle_interface::DoorStatus> sub_status_; - std::optional<autoware::component_interface_specs::vehicle_interface::DoorStatus::Message> + Cli<autoware::component_interface_specs::vehicle::DoorCommand> cli_command_; + Cli<autoware::component_interface_specs::vehicle::DoorLayout> cli_layout_; + Sub<autoware::component_interface_specs::vehicle::DoorStatus> sub_status_; + std::optional<autoware::component_interface_specs::vehicle::DoorStatus::Message> status_; }; From 8700bca0a9bf8df5cb165ccfda51ff2ec15392af Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 21 Oct 2024 22:34:15 +0000 Subject: [PATCH 3/3] style(pre-commit): autofix --- .../src/node.hpp | 6 +-- .../predicted_path_checker_node.hpp | 7 ++- .../predicted_path_checker_node.cpp | 7 ++- system/autoware_default_adapi/src/motion.cpp | 10 ++-- system/autoware_default_adapi/src/motion.hpp | 9 ++-- .../autoware_default_adapi/src/perception.cpp | 4 +- .../autoware_default_adapi/src/perception.hpp | 7 ++- .../autoware_default_adapi/src/planning.hpp | 6 +-- system/autoware_default_adapi/src/routing.hpp | 15 ++---- system/autoware_default_adapi/src/vehicle.cpp | 23 ++++---- system/autoware_default_adapi/src/vehicle.hpp | 54 ++++++++++--------- .../src/vehicle_door.cpp | 3 +- .../src/vehicle_door.hpp | 6 +-- 13 files changed, 72 insertions(+), 85 deletions(-) diff --git a/control/autoware_operation_mode_transition_manager/src/node.hpp b/control/autoware_operation_mode_transition_manager/src/node.hpp index bbfdeb6a38791..857217b2b23fc 100644 --- a/control/autoware_operation_mode_transition_manager/src/node.hpp +++ b/control/autoware_operation_mode_transition_manager/src/node.hpp @@ -37,10 +37,8 @@ class OperationModeTransitionManager : public rclcpp::Node private: using ChangeAutowareControlAPI = autoware::component_interface_specs::system::ChangeAutowareControl; - using ChangeOperationModeAPI = - autoware::component_interface_specs::system::ChangeOperationMode; - using OperationModeStateAPI = - autoware::component_interface_specs::system::OperationModeState; + using ChangeOperationModeAPI = autoware::component_interface_specs::system::ChangeOperationMode; + using OperationModeStateAPI = autoware::component_interface_specs::system::OperationModeState; component_interface_utils::Service<ChangeAutowareControlAPI>::SharedPtr srv_autoware_control_; component_interface_utils::Service<ChangeOperationModeAPI>::SharedPtr srv_operation_mode_; component_interface_utils::Publisher<OperationModeStateAPI>::SharedPtr pub_operation_mode_; 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 eed39f828873d..be3a9eace9aac 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 @@ -110,8 +110,8 @@ 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::IsStopped::Message::ConstSharedPtr - is_stopped_ptr_{nullptr}; + autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr is_stopped_ptr_{ + nullptr}; // Core std::unique_ptr<CollisionChecker> collision_checker_; @@ -130,8 +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::IsStopped::Message::ConstSharedPtr - msg); + const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr msg); // Timer rclcpp::TimerBase::SharedPtr 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 a84f84ed8edc0..4ebde9cc0fc72 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,8 +132,7 @@ void PredictedPathCheckerNode::onAccel( } void PredictedPathCheckerNode::onIsStopped( - const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr - msg) + const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr msg) { is_stopped_ptr_ = msg; @@ -416,8 +415,8 @@ void PredictedPathCheckerNode::checkVehicleState(diagnostic_updater::DiagnosticS 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::SetStop::Service::Request>(); + const auto req = + std::make_shared<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/system/autoware_default_adapi/src/motion.cpp b/system/autoware_default_adapi/src/motion.cpp index 32cb1f835bf96..2073b1dad9f77 100644 --- a/system/autoware_default_adapi/src/motion.cpp +++ b/system/autoware_default_adapi/src/motion.cpp @@ -121,8 +121,8 @@ void MotionNode::update_pause(const State state) 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::SetPause::Service::Request>(); + const auto req = + std::make_shared<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,16 +135,14 @@ void MotionNode::on_timer() } void MotionNode::on_is_paused( - const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr - msg) + const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr msg) { is_paused_ = msg->data; update_state(); } void MotionNode::on_is_start_requested( - const autoware::component_interface_specs::control::IsStartRequested::Message:: - ConstSharedPtr msg) + const autoware::component_interface_specs::control::IsStartRequested::Message::ConstSharedPtr msg) { is_start_requested_ = msg->data; update_state(); diff --git a/system/autoware_default_adapi/src/motion.hpp b/system/autoware_default_adapi/src/motion.hpp index 510353fe8da92..3854753a39cc7 100644 --- a/system/autoware_default_adapi/src/motion.hpp +++ b/system/autoware_default_adapi/src/motion.hpp @@ -41,8 +41,7 @@ class MotionNode : public rclcpp::Node Pub<autoware_ad_api::motion::State> pub_state_; Cli<autoware::component_interface_specs::control::SetPause> cli_set_pause_; Sub<autoware::component_interface_specs::control::IsPaused> sub_is_paused_; - Sub<autoware::component_interface_specs::control::IsStartRequested> - sub_is_start_requested_; + Sub<autoware::component_interface_specs::control::IsStartRequested> sub_is_start_requested_; enum class State { Unknown, Pausing, Paused, Starting, Resuming, Resumed, Moving }; State state_; @@ -59,10 +58,10 @@ class MotionNode : public rclcpp::Node void change_pause(bool pause); void on_timer(); void on_is_paused( - const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr + const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr msg); + void on_is_start_requested( + const autoware::component_interface_specs::control::IsStartRequested::Message::ConstSharedPtr msg); - 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, const autoware_ad_api::motion::AcceptStart::Service::Response::SharedPtr res); diff --git a/system/autoware_default_adapi/src/perception.cpp b/system/autoware_default_adapi/src/perception.cpp index 6432746827f20..2b4eaae0e2afb 100644 --- a/system/autoware_default_adapi/src/perception.cpp +++ b/system/autoware_default_adapi/src/perception.cpp @@ -50,8 +50,8 @@ uint8_t PerceptionNode::mapping( } void PerceptionNode::object_recognize( - const autoware::component_interface_specs::perception::ObjectRecognition::Message:: - ConstSharedPtr msg) + const autoware::component_interface_specs::perception::ObjectRecognition::Message::ConstSharedPtr + msg) { DynamicObjectArray::Message objects; objects.header = msg->header; diff --git a/system/autoware_default_adapi/src/perception.hpp b/system/autoware_default_adapi/src/perception.hpp index 2685990082bf9..af551d874663b 100644 --- a/system/autoware_default_adapi/src/perception.hpp +++ b/system/autoware_default_adapi/src/perception.hpp @@ -41,10 +41,9 @@ class PerceptionNode : public rclcpp::Node private: Pub<autoware_ad_api::perception::DynamicObjectArray> pub_object_recognized_; - Sub<autoware::component_interface_specs::perception::ObjectRecognition> - sub_object_recognized_; - void object_recognize(const autoware::component_interface_specs::perception:: - ObjectRecognition::Message::ConstSharedPtr msg); + Sub<autoware::component_interface_specs::perception::ObjectRecognition> sub_object_recognized_; + void object_recognize(const autoware::component_interface_specs::perception::ObjectRecognition:: + Message::ConstSharedPtr msg); uint8_t mapping( std::unordered_map<uint8_t, uint8_t> 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 a4e4b0fe0b408..50e044bec018c 100644 --- a/system/autoware_default_adapi/src/planning.hpp +++ b/system/autoware_default_adapi/src/planning.hpp @@ -41,8 +41,7 @@ class PlanningNode : public rclcpp::Node Pub<autoware_ad_api::planning::VelocityFactors> pub_velocity_factors_; Pub<autoware_ad_api::planning::SteeringFactors> pub_steering_factors_; Sub<autoware::component_interface_specs::planning::Trajectory> sub_trajectory_; - Sub<autoware::component_interface_specs::localization::KinematicState> - sub_kinematic_state_; + Sub<autoware::component_interface_specs::localization::KinematicState> sub_kinematic_state_; std::vector<rclcpp::Subscription<VelocityFactorArray>::SharedPtr> sub_velocity_factors_; std::vector<rclcpp::Subscription<SteeringFactorArray>::SharedPtr> sub_steering_factors_; std::vector<VelocityFactorArray::ConstSharedPtr> velocity_factors_; @@ -51,8 +50,7 @@ class PlanningNode : public rclcpp::Node using VehicleStopChecker = autoware::motion_utils::VehicleStopCheckerBase; using Trajectory = autoware::component_interface_specs::planning::Trajectory::Message; - using KinematicState = - autoware::component_interface_specs::localization::KinematicState::Message; + using KinematicState = 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.hpp b/system/autoware_default_adapi/src/routing.hpp index 9de3f312e5b39..b78237697dcf0 100644 --- a/system/autoware_default_adapi/src/routing.hpp +++ b/system/autoware_default_adapi/src/routing.hpp @@ -33,8 +33,7 @@ class RoutingNode : public rclcpp::Node explicit RoutingNode(const rclcpp::NodeOptions & options); private: - using OperationModeState = - autoware::component_interface_specs::system::OperationModeState; + using OperationModeState = autoware::component_interface_specs::system::OperationModeState; using State = autoware::component_interface_specs::planning::RouteState; using Route = autoware::component_interface_specs::planning::LaneletRoute; @@ -48,15 +47,11 @@ class RoutingNode : public rclcpp::Node Srv<autoware_ad_api::routing::ClearRoute> srv_clear_route_; Sub<autoware::component_interface_specs::planning::RouteState> sub_state_; Sub<autoware::component_interface_specs::planning::LaneletRoute> sub_route_; - Cli<autoware::component_interface_specs::planning::SetWaypointRoute> - cli_set_waypoint_route_; - Cli<autoware::component_interface_specs::planning::SetLaneletRoute> - cli_set_lanelet_route_; + Cli<autoware::component_interface_specs::planning::SetWaypointRoute> cli_set_waypoint_route_; + Cli<autoware::component_interface_specs::planning::SetLaneletRoute> cli_set_lanelet_route_; Cli<autoware::component_interface_specs::planning::ClearRoute> cli_clear_route_; - Cli<autoware::component_interface_specs::system::ChangeOperationMode> - cli_operation_mode_; - Sub<autoware::component_interface_specs::system::OperationModeState> - sub_operation_mode_; + Cli<autoware::component_interface_specs::system::ChangeOperationMode> cli_operation_mode_; + Sub<autoware::component_interface_specs::system::OperationModeState> 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 bc0a7b9cf8110..a38bf9cb9a9b3 100644 --- a/system/autoware_default_adapi/src/vehicle.cpp +++ b/system/autoware_default_adapi/src/vehicle.cpp @@ -29,11 +29,9 @@ using ApiGear = autoware_adapi_v1_msgs::msg::Gear; using TurnIndicatorsReport = autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message; using ApiTurnIndicator = autoware_adapi_v1_msgs::msg::TurnIndicators; -using HazardLightsReport = - autoware::component_interface_specs::vehicle::HazardLightStatus::Message; +using HazardLightsReport = autoware::component_interface_specs::vehicle::HazardLightStatus::Message; using ApiHazardLight = autoware_adapi_v1_msgs::msg::HazardLights; -using MapProjectorInfo = - autoware::component_interface_specs::map::MapProjectorInfo::Message; +using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo::Message; std::unordered_map<uint8_t, uint8_t> gear_type_ = { {GearReport::NONE, ApiGear::UNKNOWN}, {GearReport::NEUTRAL, ApiGear::NEUTRAL}, @@ -92,21 +90,22 @@ uint8_t VehicleNode::mapping( } void VehicleNode::kinematic_state( - const autoware::component_interface_specs::localization::KinematicState::Message:: - ConstSharedPtr msg_ptr) + 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::Acceleration::Message:: - ConstSharedPtr msg_ptr) + 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:: - SteeringStatus::Message::ConstSharedPtr msg_ptr) +void VehicleNode::steering_status( + const autoware::component_interface_specs::vehicle::SteeringStatus::Message::ConstSharedPtr + msg_ptr) { steering_status_msgs_ = msg_ptr; } @@ -126,8 +125,8 @@ 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:: - EnergyStatus::Message::ConstSharedPtr msg_ptr) +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 873d53a142394..ad03aac9116ea 100644 --- a/system/autoware_default_adapi/src/vehicle.hpp +++ b/system/autoware_default_adapi/src/vehicle.hpp @@ -42,28 +42,26 @@ class VehicleNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Pub<autoware_ad_api::vehicle::VehicleKinematics> pub_kinematics_; Pub<autoware_ad_api::vehicle::VehicleStatus> pub_status_; - Sub<autoware::component_interface_specs::localization::KinematicState> - sub_kinematic_state_; + Sub<autoware::component_interface_specs::localization::KinematicState> sub_kinematic_state_; Sub<autoware::component_interface_specs::localization::Acceleration> sub_acceleration_; Sub<autoware::component_interface_specs::vehicle::SteeringStatus> sub_steering_; Sub<autoware::component_interface_specs::vehicle::GearStatus> sub_gear_state_; - Sub<autoware::component_interface_specs::vehicle::TurnIndicatorStatus> - sub_turn_indicator_; + Sub<autoware::component_interface_specs::vehicle::TurnIndicatorStatus> sub_turn_indicator_; Sub<autoware::component_interface_specs::vehicle::HazardLightStatus> sub_hazard_light_; Sub<autoware::component_interface_specs::vehicle::EnergyStatus> sub_energy_level_; Sub<autoware::component_interface_specs::map::MapProjectorInfo> sub_map_projector_info_; rclcpp::TimerBase::SharedPtr timer_; - autoware::component_interface_specs::localization::KinematicState::Message:: - ConstSharedPtr kinematic_state_msgs_; + autoware::component_interface_specs::localization::KinematicState::Message::ConstSharedPtr + kinematic_state_msgs_; autoware::component_interface_specs::localization::Acceleration::Message::ConstSharedPtr acceleration_msgs_; autoware::component_interface_specs::vehicle::SteeringStatus::Message::ConstSharedPtr steering_status_msgs_; autoware::component_interface_specs::vehicle::GearStatus::Message::ConstSharedPtr gear_status_msgs_; - autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message:: - ConstSharedPtr turn_indicator_status_msgs_; + autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message::ConstSharedPtr + turn_indicator_status_msgs_; autoware::component_interface_specs::vehicle::HazardLightStatus::Message::ConstSharedPtr hazard_light_status_msgs_; autoware::component_interface_specs::vehicle::EnergyStatus::Message::ConstSharedPtr @@ -71,22 +69,30 @@ class VehicleNode : public rclcpp::Node autoware::component_interface_specs::map::MapProjectorInfo::Message::ConstSharedPtr map_projector_info_; - void kinematic_state(const autoware::component_interface_specs::localization:: - KinematicState::Message::ConstSharedPtr msg_ptr); - void acceleration_status(const autoware::component_interface_specs::localization:: - Acceleration::Message::ConstSharedPtr msg_ptr); - void steering_status(const autoware::component_interface_specs::vehicle:: - SteeringStatus::Message::ConstSharedPtr msg_ptr); - void gear_status(const autoware::component_interface_specs::vehicle::GearStatus:: - Message::ConstSharedPtr msg_ptr); - 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:: - MapProjectorInfo::Message::ConstSharedPtr msg_ptr); - void hazard_light_status(const autoware::component_interface_specs::vehicle:: - HazardLightStatus::Message::ConstSharedPtr msg_ptr); - void energy_status(const autoware::component_interface_specs::vehicle::EnergyStatus:: - Message::ConstSharedPtr msg_ptr); + void kinematic_state( + const autoware::component_interface_specs::localization::KinematicState::Message::ConstSharedPtr + msg_ptr); + void acceleration_status( + const autoware::component_interface_specs::localization::Acceleration::Message::ConstSharedPtr + msg_ptr); + void steering_status( + const autoware::component_interface_specs::vehicle::SteeringStatus::Message::ConstSharedPtr + msg_ptr); + void gear_status( + const autoware::component_interface_specs::vehicle::GearStatus::Message::ConstSharedPtr + msg_ptr); + 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::MapProjectorInfo::Message::ConstSharedPtr + msg_ptr); + void hazard_light_status( + const autoware::component_interface_specs::vehicle::HazardLightStatus::Message::ConstSharedPtr + msg_ptr); + void energy_status( + const autoware::component_interface_specs::vehicle::EnergyStatus::Message::ConstSharedPtr + msg_ptr); uint8_t mapping( std::unordered_map<uint8_t, uint8_t> hash_map, uint8_t input, uint8_t default_value); void publish_kinematics(); diff --git a/system/autoware_default_adapi/src/vehicle_door.cpp b/system/autoware_default_adapi/src/vehicle_door.cpp index 8c0c63c972de4..259ef907097de 100644 --- a/system/autoware_default_adapi/src/vehicle_door.cpp +++ b/system/autoware_default_adapi/src/vehicle_door.cpp @@ -35,8 +35,7 @@ void VehicleDoorNode::on_status( { utils::notify( pub_status_, status_, *msg, - utils::ignore_stamp< - autoware::component_interface_specs::vehicle::DoorStatus::Message>); + utils::ignore_stamp<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 404a65f7ad95f..9b04b08adb438 100644 --- a/system/autoware_default_adapi/src/vehicle_door.hpp +++ b/system/autoware_default_adapi/src/vehicle_door.hpp @@ -34,8 +34,7 @@ class VehicleDoorNode : public rclcpp::Node private: void on_status( - autoware::component_interface_specs::vehicle::DoorStatus::Message::ConstSharedPtr - msg); + autoware::component_interface_specs::vehicle::DoorStatus::Message::ConstSharedPtr msg); rclcpp::CallbackGroup::SharedPtr group_cli_; Srv<autoware_ad_api::vehicle::DoorCommand> srv_command_; Srv<autoware_ad_api::vehicle::DoorLayout> srv_layout_; @@ -43,8 +42,7 @@ class VehicleDoorNode : public rclcpp::Node Cli<autoware::component_interface_specs::vehicle::DoorCommand> cli_command_; Cli<autoware::component_interface_specs::vehicle::DoorLayout> cli_layout_; Sub<autoware::component_interface_specs::vehicle::DoorStatus> sub_status_; - std::optional<autoware::component_interface_specs::vehicle::DoorStatus::Message> - status_; + std::optional<autoware::component_interface_specs::vehicle::DoorStatus::Message> status_; }; } // namespace autoware::default_adapi