From 187fc812c3d16f008cc472673ffd9477d4250f51 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Thu, 22 Aug 2024 18:43:19 +0900 Subject: [PATCH] refactor(pose_estimator_arbiter)!: prefix package and namespace with autoware (#8386) * add autoware_ prefix Signed-off-by: a-maumau * add autoware_ prefix Signed-off-by: a-maumau * fix link for landmark_based_localizer Signed-off-by: a-maumau * remove Shadowing Signed-off-by: a-maumau --------- Signed-off-by: a-maumau Co-authored-by: SakodaShintaro --- .../pose_twist_estimator.launch.xml | 2 +- launch/tier4_localization_launch/package.xml | 2 +- .../CMakeLists.txt | 13 ++++--- .../README.md | 26 ++++++------- .../example_rule/CMakeLists.txt | 12 +++--- .../example_rule/README.md | 0 .../src}/rule_helper/grid_key.hpp | 14 +++---- .../src}/rule_helper/pcd_occupancy.cpp | 8 ++-- .../src}/rule_helper/pcd_occupancy.hpp | 10 ++--- .../src}/rule_helper/pose_estimator_area.cpp | 6 +-- .../src}/rule_helper/pose_estimator_area.hpp | 10 ++--- .../src}/switch_rule/pcd_map_based_rule.cpp | 6 +-- .../src}/switch_rule/pcd_map_based_rule.hpp | 18 ++++----- .../switch_rule/vector_map_based_rule.cpp | 6 +-- .../switch_rule/vector_map_based_rule.hpp | 18 ++++----- .../test/test_pcd_map_based_rule.cpp | 36 +++++++++--------- .../example_rule/test/test_rule_helper.cpp | 14 +++---- .../test/test_vector_map_based_rule.cpp | 36 +++++++++--------- .../launch/pose_estimator_arbiter.launch.xml | 2 +- .../media/architecture.drawio.svg | 0 .../media/pcd_occupancy.drawio.svg | 0 .../pose_estimator_area_in_vector_map.png | Bin .../media/single_pose_estimator.drawio.svg | 0 .../package.xml | 2 +- .../src}/pose_estimator_arbiter.hpp | 16 ++++---- .../src}/pose_estimator_arbiter_core.cpp | 26 ++++++------- .../src}/pose_estimator_type.hpp | 10 ++--- .../src}/shared_data.hpp | 10 ++--- .../src}/stopper/base_stopper.hpp | 12 +++--- .../src}/stopper/stopper_artag.hpp | 12 +++--- .../src}/stopper/stopper_eagleye.hpp | 12 +++--- .../src}/stopper/stopper_ndt.hpp | 12 +++--- .../src}/stopper/stopper_yabloc.hpp | 12 +++--- .../src}/switch_rule/base_switch_rule.hpp | 15 ++++---- .../src}/switch_rule/enable_all_rule.cpp | 6 +-- .../src}/switch_rule/enable_all_rule.hpp | 14 +++---- .../test/test_pose_estimator_arbiter.py | 2 +- .../test/test_shared_data.cpp | 6 +-- 38 files changed, 205 insertions(+), 201 deletions(-) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/CMakeLists.txt (83%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/README.md (94%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/example_rule/CMakeLists.txt (67%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/example_rule/README.md (100%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/rule_helper/grid_key.hpp (78%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/rule_helper/pcd_occupancy.cpp (93%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/rule_helper/pcd_occupancy.hpp (83%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/rule_helper/pose_estimator_area.cpp (96%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/rule_helper/pose_estimator_area.hpp (83%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/switch_rule/pcd_map_based_rule.cpp (93%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/switch_rule/pcd_map_based_rule.hpp (71%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/switch_rule/vector_map_based_rule.cpp (93%) rename localization/{pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/example_rule/src}/switch_rule/vector_map_based_rule.hpp (71%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/example_rule/test/test_pcd_map_based_rule.cpp (62%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/example_rule/test/test_rule_helper.cpp (87%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/example_rule/test/test_vector_map_based_rule.cpp (65%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/launch/pose_estimator_arbiter.launch.xml (93%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/media/architecture.drawio.svg (100%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/media/pcd_occupancy.drawio.svg (100%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/media/pose_estimator_area_in_vector_map.png (100%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/media/single_pose_estimator.drawio.svg (100%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/package.xml (97%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/pose_estimator_arbiter.hpp (89%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/pose_estimator_arbiter_core.cpp (90%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/pose_estimator_type.hpp (73%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/shared_data.hpp (93%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/stopper/base_stopper.hpp (81%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/stopper/stopper_artag.hpp (82%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/stopper/stopper_eagleye.hpp (81%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/stopper/stopper_ndt.hpp (81%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/stopper/stopper_yabloc.hpp (89%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/switch_rule/base_switch_rule.hpp (78%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/switch_rule/enable_all_rule.cpp (88%) rename localization/{pose_estimator_arbiter/src/pose_estimator_arbiter => autoware_pose_estimator_arbiter/src}/switch_rule/enable_all_rule.hpp (71%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/test/test_pose_estimator_arbiter.py (98%) rename localization/{pose_estimator_arbiter => autoware_pose_estimator_arbiter}/test/test_shared_data.cpp (90%) diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml index fa6bce0e38e55..f06c9f83efb35 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml @@ -93,7 +93,7 @@ - + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 19d15b43e5d14..efeecd3e37f61 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -22,12 +22,12 @@ autoware_geo_pose_projector autoware_gyro_odometer autoware_pointcloud_preprocessor + autoware_pose_estimator_arbiter eagleye_geo_pose_fusion eagleye_gnss_converter eagleye_rt ekf_localizer ndt_scan_matcher - pose_estimator_arbiter pose_initializer pose_instability_detector topic_tools diff --git a/localization/pose_estimator_arbiter/CMakeLists.txt b/localization/autoware_pose_estimator_arbiter/CMakeLists.txt similarity index 83% rename from localization/pose_estimator_arbiter/CMakeLists.txt rename to localization/autoware_pose_estimator_arbiter/CMakeLists.txt index eefb7fc9a6879..a45da8767b72b 100644 --- a/localization/pose_estimator_arbiter/CMakeLists.txt +++ b/localization/autoware_pose_estimator_arbiter/CMakeLists.txt @@ -1,22 +1,25 @@ cmake_minimum_required(VERSION 3.14) -project(pose_estimator_arbiter) +project(autoware_pose_estimator_arbiter) find_package(autoware_cmake REQUIRED) autoware_package() find_package(PCL REQUIRED COMPONENTS common) -include_directories(SYSTEM ${PCL_INCLUDE_DIRS}) +include_directories( + SYSTEM ${PCL_INCLUDE_DIRS} + src +) # ============================== # pose estimator arbiter node ament_auto_add_library(${PROJECT_NAME} SHARED - src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp - src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp + src/pose_estimator_arbiter_core.cpp + src/switch_rule/enable_all_rule.cpp ) target_include_directories(${PROJECT_NAME} PUBLIC src) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "pose_estimator_arbiter::PoseEstimatorArbiter" + PLUGIN "autoware::pose_estimator_arbiter::PoseEstimatorArbiter" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR MultiThreadedExecutor ) diff --git a/localization/pose_estimator_arbiter/README.md b/localization/autoware_pose_estimator_arbiter/README.md similarity index 94% rename from localization/pose_estimator_arbiter/README.md rename to localization/autoware_pose_estimator_arbiter/README.md index 7b9397dfdba47..938bb20e252ac 100644 --- a/localization/pose_estimator_arbiter/README.md +++ b/localization/autoware_pose_estimator_arbiter/README.md @@ -1,4 +1,4 @@ -# pose_estimator_arbiter +# autoware_pose_estimator_arbiter Table of contents: @@ -35,7 +35,7 @@ Also, even if both can be activated at the same time, the Kalman Filter may be a - [ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) - [eagleye](https://autowarefoundation.github.io/autoware-documentation/main/how-to-guides/integrating-autoware/launch-autoware/localization/eagleye/) - [yabloc](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/yabloc) -- [landmark_based_localizer](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/landmark_based_localizer) +- [landmark_based_localizer](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/autoware_landmark_based_localizer) ### Demonstration @@ -117,8 +117,8 @@ If it does not seems to work, users can get more information in the following wa > [!TIP] > > ```bash -> ros2 service call /localization/pose_estimator_arbiter/config_logger logging_demo/srv/ConfigLogger \ -> '{logger_name: localization.pose_estimator_arbiter, level: debug}' +> ros2 service call /localization/autoware_pose_estimator_arbiter/config_logger logging_demo/srv/ConfigLogger \ +> '{logger_name: localization.autoware_pose_estimator_arbiter, level: debug}' > ``` ## Architecture @@ -135,7 +135,7 @@ Following figure shows the node configuration when NDT, YabLoc Eagleye and AR-Ta ### Case of running multiple pose estimators -When running multiple pose_estimators, pose_estimator_arbiter is executed. +When running multiple pose_estimators, autoware_pose_estimator_arbiter is executed. It comprises a **switching rule** and **stoppers** corresponding to each pose_estimator. - Stoppers control the pose_estimator activity by relaying inputs or outputs, or by requesting a suspend service. @@ -187,14 +187,14 @@ ros2 launch autoware_launch logging_simulator.launch.xml \ Even if `pose_source` includes an unexpected string, it will be filtered appropriately. Please see the table below for details. -| given runtime argument | parsed pose_estimator_arbiter's param (pose_sources) | -| ------------------------------------------- | ---------------------------------------------------- | -| `pose_source:=ndt` | `["ndt"]` | -| `pose_source:=nan` | `[]` | -| `pose_source:=yabloc_ndt` | `["ndt","yabloc"]` | -| `pose_source:=yabloc_ndt_ndt_ndt` | `["ndt","yabloc"]` | -| `pose_source:=ndt_yabloc_eagleye` | `["ndt","yabloc","eagleye"]` | -| `pose_source:=ndt_yabloc_nan_eagleye_artag` | `["ndt","yabloc","eagleye","artag"]` | +| given runtime argument | parsed autoware_pose_estimator_arbiter's param (pose_sources) | +| ------------------------------------------- | ------------------------------------------------------------- | +| `pose_source:=ndt` | `["ndt"]` | +| `pose_source:=nan` | `[]` | +| `pose_source:=yabloc_ndt` | `["ndt","yabloc"]` | +| `pose_source:=yabloc_ndt_ndt_ndt` | `["ndt","yabloc"]` | +| `pose_source:=ndt_yabloc_eagleye` | `["ndt","yabloc","eagleye"]` | +| `pose_source:=ndt_yabloc_nan_eagleye_artag` | `["ndt","yabloc","eagleye","artag"]` | diff --git a/localization/pose_estimator_arbiter/example_rule/CMakeLists.txt b/localization/autoware_pose_estimator_arbiter/example_rule/CMakeLists.txt similarity index 67% rename from localization/pose_estimator_arbiter/example_rule/CMakeLists.txt rename to localization/autoware_pose_estimator_arbiter/example_rule/CMakeLists.txt index b2b5a828e42e7..5125829ffd69c 100644 --- a/localization/pose_estimator_arbiter/example_rule/CMakeLists.txt +++ b/localization/autoware_pose_estimator_arbiter/example_rule/CMakeLists.txt @@ -1,13 +1,13 @@ # example switch rule library ament_auto_add_library(example_rule SHARED - src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp - src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp - src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp - src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp + src/switch_rule/pcd_map_based_rule.cpp + src/switch_rule/vector_map_based_rule.cpp + src/rule_helper/pcd_occupancy.cpp + src/rule_helper/pose_estimator_area.cpp ) target_include_directories(example_rule PUBLIC src example_rule/src) -target_link_libraries(example_rule pose_estimator_arbiter) +target_link_libraries(example_rule autoware_pose_estimator_arbiter) # ============================== # define test definition macro @@ -16,7 +16,7 @@ function(add_testcase filepath) string(REGEX REPLACE ".cpp" "" test_name ${filename}) ament_add_gtest(${test_name} ${filepath}) - target_link_libraries("${test_name}" pose_estimator_arbiter example_rule) + target_link_libraries("${test_name}" autoware_pose_estimator_arbiter example_rule) target_include_directories(${test_name} PUBLIC src) ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) endfunction() diff --git a/localization/pose_estimator_arbiter/example_rule/README.md b/localization/autoware_pose_estimator_arbiter/example_rule/README.md similarity index 100% rename from localization/pose_estimator_arbiter/example_rule/README.md rename to localization/autoware_pose_estimator_arbiter/example_rule/README.md diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/grid_key.hpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/grid_key.hpp similarity index 78% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/grid_key.hpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/grid_key.hpp index b4ad7111e4ba0..d4d4409ade979 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/grid_key.hpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/grid_key.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__RULE_HELPER__GRID_KEY_HPP_ -#define POSE_ESTIMATOR_ARBITER__RULE_HELPER__GRID_KEY_HPP_ +#ifndef RULE_HELPER__GRID_KEY_HPP_ +#define RULE_HELPER__GRID_KEY_HPP_ #include #include #include -namespace pose_estimator_arbiter::rule_helper +namespace autoware::pose_estimator_arbiter::rule_helper { struct GridKey { @@ -46,16 +46,16 @@ struct GridKey friend bool operator!=(const GridKey & one, const GridKey & other) { return !(one == other); } }; -} // namespace pose_estimator_arbiter::rule_helper +} // namespace autoware::pose_estimator_arbiter::rule_helper // This is for unordered_map and unordered_set namespace std { template <> -struct hash +struct hash { public: - size_t operator()(const pose_estimator_arbiter::rule_helper::GridKey & grid) const + size_t operator()(const autoware::pose_estimator_arbiter::rule_helper::GridKey & grid) const { std::size_t seed = 0; boost::hash_combine(seed, grid.x); @@ -65,4 +65,4 @@ struct hash }; } // namespace std -#endif // POSE_ESTIMATOR_ARBITER__RULE_HELPER__GRID_KEY_HPP_ +#endif // RULE_HELPER__GRID_KEY_HPP_ diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pcd_occupancy.cpp similarity index 93% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pcd_occupancy.cpp index 4b0188a1638f6..197bff459530d 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pcd_occupancy.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp" +#include "rule_helper/pcd_occupancy.hpp" -#include "pose_estimator_arbiter/rule_helper/grid_key.hpp" +#include "rule_helper/grid_key.hpp" #include @@ -25,7 +25,7 @@ #include #include -namespace pose_estimator_arbiter::rule_helper +namespace autoware::pose_estimator_arbiter::rule_helper { PcdOccupancy::PcdOccupancy(int pcd_density_upper_threshold, int pcd_density_lower_threshold) : pcd_density_upper_threshold_(pcd_density_upper_threshold), @@ -114,4 +114,4 @@ void PcdOccupancy::init(PointCloud2::ConstSharedPtr msg) kdtree_->setInputCloud(occupied_areas_); } -} // namespace pose_estimator_arbiter::rule_helper +} // namespace autoware::pose_estimator_arbiter::rule_helper diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pcd_occupancy.hpp similarity index 83% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pcd_occupancy.hpp index 098704e11aba9..e38cb1bd1ee38 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pcd_occupancy.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__RULE_HELPER__PCD_OCCUPANCY_HPP_ -#define POSE_ESTIMATOR_ARBITER__RULE_HELPER__PCD_OCCUPANCY_HPP_ +#ifndef RULE_HELPER__PCD_OCCUPANCY_HPP_ +#define RULE_HELPER__PCD_OCCUPANCY_HPP_ #include @@ -26,7 +26,7 @@ #include -namespace pose_estimator_arbiter::rule_helper +namespace autoware::pose_estimator_arbiter::rule_helper { class PcdOccupancy { @@ -49,6 +49,6 @@ class PcdOccupancy pcl::KdTreeFLANN::Ptr kdtree_{nullptr}; }; -} // namespace pose_estimator_arbiter::rule_helper +} // namespace autoware::pose_estimator_arbiter::rule_helper -#endif // POSE_ESTIMATOR_ARBITER__RULE_HELPER__PCD_OCCUPANCY_HPP_ +#endif // RULE_HELPER__PCD_OCCUPANCY_HPP_ diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.cpp similarity index 96% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.cpp index 1bf359b6ab54d..41ad45430d238 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp" +#include "rule_helper/pose_estimator_area.hpp" #include #include @@ -26,7 +26,7 @@ #include #include -namespace pose_estimator_arbiter::rule_helper +namespace autoware::pose_estimator_arbiter::rule_helper { using BoostPoint = boost::geometry::model::d2::point_xy; using BoostPolygon = boost::geometry::model::polygon; @@ -141,4 +141,4 @@ bool PoseEstimatorArea::Impl::within( } return false; } -} // namespace pose_estimator_arbiter::rule_helper +} // namespace autoware::pose_estimator_arbiter::rule_helper diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.hpp similarity index 83% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.hpp index 74843c66a4eba..262b064615bc1 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__RULE_HELPER__POSE_ESTIMATOR_AREA_HPP_ -#define POSE_ESTIMATOR_ARBITER__RULE_HELPER__POSE_ESTIMATOR_AREA_HPP_ +#ifndef RULE_HELPER__POSE_ESTIMATOR_AREA_HPP_ +#define RULE_HELPER__POSE_ESTIMATOR_AREA_HPP_ #include #include @@ -25,7 +25,7 @@ #include #include -namespace pose_estimator_arbiter::rule_helper +namespace autoware::pose_estimator_arbiter::rule_helper { class PoseEstimatorArea { @@ -51,6 +51,6 @@ class PoseEstimatorArea rclcpp::Logger logger_; }; -} // namespace pose_estimator_arbiter::rule_helper +} // namespace autoware::pose_estimator_arbiter::rule_helper -#endif // POSE_ESTIMATOR_ARBITER__RULE_HELPER__POSE_ESTIMATOR_AREA_HPP_ +#endif // RULE_HELPER__POSE_ESTIMATOR_AREA_HPP_ diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.cpp similarity index 93% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.cpp index 3a565e7f2e4df..cc5414ebd0a68 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp" +#include "switch_rule/pcd_map_based_rule.hpp" #include #include -namespace pose_estimator_arbiter::switch_rule +namespace autoware::pose_estimator_arbiter::switch_rule { PcdMapBasedRule::PcdMapBasedRule( rclcpp::Node & node, std::unordered_set running_estimator_list, @@ -77,4 +77,4 @@ std::unordered_map PcdMapBasedRule::update() {PoseEstimatorType::artag, false}}; } -} // namespace pose_estimator_arbiter::switch_rule +} // namespace autoware::pose_estimator_arbiter::switch_rule diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.hpp similarity index 71% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.hpp index ab4d18dcad66a..45559fe37e606 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.hpp @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__SWITCH_RULE__PCD_MAP_BASED_RULE_HPP_ -#define POSE_ESTIMATOR_ARBITER__SWITCH_RULE__PCD_MAP_BASED_RULE_HPP_ +#ifndef SWITCH_RULE__PCD_MAP_BASED_RULE_HPP_ +#define SWITCH_RULE__PCD_MAP_BASED_RULE_HPP_ -#include "pose_estimator_arbiter/pose_estimator_type.hpp" -#include "pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp" -#include "pose_estimator_arbiter/shared_data.hpp" -#include "pose_estimator_arbiter/switch_rule/base_switch_rule.hpp" +#include "pose_estimator_type.hpp" +#include "rule_helper/pcd_occupancy.hpp" +#include "shared_data.hpp" +#include "switch_rule/base_switch_rule.hpp" #include #include #include #include -namespace pose_estimator_arbiter::switch_rule +namespace autoware::pose_estimator_arbiter::switch_rule { class PcdMapBasedRule : public BaseSwitchRule { @@ -49,6 +49,6 @@ class PcdMapBasedRule : public BaseSwitchRule // Store the reason why which pose estimator is enabled mutable std::string debug_string_; }; -} // namespace pose_estimator_arbiter::switch_rule +} // namespace autoware::pose_estimator_arbiter::switch_rule -#endif // POSE_ESTIMATOR_ARBITER__SWITCH_RULE__PCD_MAP_BASED_RULE_HPP_ +#endif // SWITCH_RULE__PCD_MAP_BASED_RULE_HPP_ diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.cpp similarity index 93% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.cpp index dffb738e87685..58cf9ab09e9a7 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp" +#include "switch_rule/vector_map_based_rule.hpp" #include #include -namespace pose_estimator_arbiter::switch_rule +namespace autoware::pose_estimator_arbiter::switch_rule { VectorMapBasedRule::VectorMapBasedRule( rclcpp::Node & node, std::unordered_set running_estimator_list, @@ -76,4 +76,4 @@ std::unordered_map VectorMapBasedRule::update() return enable_list; } -} // namespace pose_estimator_arbiter::switch_rule +} // namespace autoware::pose_estimator_arbiter::switch_rule diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.hpp similarity index 71% rename from localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp rename to localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.hpp index 83723a346054b..356651af223f3 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__SWITCH_RULE__VECTOR_MAP_BASED_RULE_HPP_ -#define POSE_ESTIMATOR_ARBITER__SWITCH_RULE__VECTOR_MAP_BASED_RULE_HPP_ +#ifndef SWITCH_RULE__VECTOR_MAP_BASED_RULE_HPP_ +#define SWITCH_RULE__VECTOR_MAP_BASED_RULE_HPP_ -#include "pose_estimator_arbiter/pose_estimator_type.hpp" -#include "pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp" -#include "pose_estimator_arbiter/shared_data.hpp" -#include "pose_estimator_arbiter/switch_rule/base_switch_rule.hpp" +#include "pose_estimator_type.hpp" +#include "rule_helper/pose_estimator_area.hpp" +#include "shared_data.hpp" +#include "switch_rule/base_switch_rule.hpp" #include #include @@ -26,7 +26,7 @@ #include #include -namespace pose_estimator_arbiter::switch_rule +namespace autoware::pose_estimator_arbiter::switch_rule { class VectorMapBasedRule : public BaseSwitchRule { @@ -50,6 +50,6 @@ class VectorMapBasedRule : public BaseSwitchRule std::unique_ptr pose_estimator_area_{nullptr}; }; -} // namespace pose_estimator_arbiter::switch_rule +} // namespace autoware::pose_estimator_arbiter::switch_rule -#endif // POSE_ESTIMATOR_ARBITER__SWITCH_RULE__VECTOR_MAP_BASED_RULE_HPP_ +#endif // SWITCH_RULE__VECTOR_MAP_BASED_RULE_HPP_ diff --git a/localization/pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp similarity index 62% rename from localization/pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp rename to localization/autoware_pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp index f53e01dc9c548..0d1f245123806 100644 --- a/localization/pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/switch_rule/pcd_map_based_rule.hpp" +#include "switch_rule/pcd_map_based_rule.hpp" #include #include @@ -30,21 +30,21 @@ class PcdMapBasedRuleMockNode : public ::testing::Test node->declare_parameter("pcd_density_upper_threshold", 5); const auto running_estimator_list = - std::unordered_set{ - pose_estimator_arbiter::PoseEstimatorType::ndt, - pose_estimator_arbiter::PoseEstimatorType::yabloc, - pose_estimator_arbiter::PoseEstimatorType::eagleye, - pose_estimator_arbiter::PoseEstimatorType::artag}; + std::unordered_set{ + autoware::pose_estimator_arbiter::PoseEstimatorType::ndt, + autoware::pose_estimator_arbiter::PoseEstimatorType::yabloc, + autoware::pose_estimator_arbiter::PoseEstimatorType::eagleye, + autoware::pose_estimator_arbiter::PoseEstimatorType::artag}; - shared_data_ = std::make_shared(); + shared_data_ = std::make_shared(); - rule_ = std::make_shared( + rule_ = std::make_shared( *node, running_estimator_list, shared_data_); } std::shared_ptr node; - std::shared_ptr shared_data_; - std::shared_ptr rule_; + std::shared_ptr shared_data_; + std::shared_ptr rule_; void TearDown() override { rclcpp::shutdown(); } }; @@ -81,10 +81,10 @@ TEST_F(PcdMapBasedRuleMockNode, pcdMapBasedRule) shared_data_->localization_pose_cov.set_and_invoke( std::make_shared(position)); auto ret = rule_->update(); - EXPECT_TRUE(ret.at(pose_estimator_arbiter::PoseEstimatorType::ndt)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::yabloc)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::eagleye)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::artag)); + EXPECT_TRUE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::ndt)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::yabloc)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::eagleye)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::artag)); } { @@ -92,9 +92,9 @@ TEST_F(PcdMapBasedRuleMockNode, pcdMapBasedRule) shared_data_->localization_pose_cov.set_and_invoke( std::make_shared(position)); auto ret = rule_->update(); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::ndt)); - EXPECT_TRUE(ret.at(pose_estimator_arbiter::PoseEstimatorType::yabloc)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::eagleye)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::artag)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::ndt)); + EXPECT_TRUE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::yabloc)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::eagleye)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::artag)); } } diff --git a/localization/pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp similarity index 87% rename from localization/pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp rename to localization/autoware_pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp index 3258a1be34fda..10833b5498b89 100644 --- a/localization/pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/rule_helper/grid_key.hpp" -#include "pose_estimator_arbiter/rule_helper/pcd_occupancy.hpp" -#include "pose_estimator_arbiter/rule_helper/pose_estimator_area.hpp" +#include "rule_helper/grid_key.hpp" +#include "rule_helper/pcd_occupancy.hpp" +#include "rule_helper/pose_estimator_area.hpp" #include @@ -64,7 +64,7 @@ TEST_F(RuleHelperMockNode, poseEstimatorArea) HADMapBin msg; lanelet::utils::conversion::toBinMsg(lanelet_map, &msg); - pose_estimator_arbiter::rule_helper::PoseEstimatorArea pose_estimator_area(&(*node)); + autoware::pose_estimator_arbiter::rule_helper::PoseEstimatorArea pose_estimator_area(&(*node)); pose_estimator_area.init(std::make_shared(msg)); EXPECT_TRUE(pose_estimator_area.within(Point().set__x(5).set__y(5).set__z(0), "ndt")); @@ -75,11 +75,11 @@ TEST_F(RuleHelperMockNode, poseEstimatorArea) TEST_F(RuleHelperMockNode, pcdOccupancy) { - using pose_estimator_arbiter::rule_helper::PcdOccupancy; + using autoware::pose_estimator_arbiter::rule_helper::PcdOccupancy; const int pcd_density_upper_threshold = 20; const int pcd_density_lower_threshold = 10; - pose_estimator_arbiter::rule_helper::PcdOccupancy pcd_occupancy( + autoware::pose_estimator_arbiter::rule_helper::PcdOccupancy pcd_occupancy( pcd_density_upper_threshold, pcd_density_lower_threshold); geometry_msgs::msg::Point point; @@ -91,7 +91,7 @@ TEST_F(RuleHelperMockNode, pcdOccupancy) TEST_F(RuleHelperMockNode, gridKey) { - using pose_estimator_arbiter::rule_helper::GridKey; + using autoware::pose_estimator_arbiter::rule_helper::GridKey; EXPECT_TRUE(GridKey(10., -5.) == GridKey(10., -10.)); EXPECT_TRUE(GridKey(10., -5.) != GridKey(10., -15.)); diff --git a/localization/pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp similarity index 65% rename from localization/pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp rename to localization/autoware_pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp index ec8c905bf8311..9d537f2048176 100644 --- a/localization/pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/switch_rule/vector_map_based_rule.hpp" +#include "switch_rule/vector_map_based_rule.hpp" #include @@ -33,21 +33,21 @@ class VectorMapBasedRuleMockNode : public ::testing::Test node = std::make_shared("test_node"); const auto running_estimator_list = - std::unordered_set{ - pose_estimator_arbiter::PoseEstimatorType::ndt, - pose_estimator_arbiter::PoseEstimatorType::yabloc, - pose_estimator_arbiter::PoseEstimatorType::eagleye, - pose_estimator_arbiter::PoseEstimatorType::artag}; + std::unordered_set{ + autoware::pose_estimator_arbiter::PoseEstimatorType::ndt, + autoware::pose_estimator_arbiter::PoseEstimatorType::yabloc, + autoware::pose_estimator_arbiter::PoseEstimatorType::eagleye, + autoware::pose_estimator_arbiter::PoseEstimatorType::artag}; - shared_data_ = std::make_shared(); + shared_data_ = std::make_shared(); - rule_ = std::make_shared( + rule_ = std::make_shared( *node, running_estimator_list, shared_data_); } std::shared_ptr node; - std::shared_ptr shared_data_; - std::shared_ptr rule_; + std::shared_ptr shared_data_; + std::shared_ptr rule_; void TearDown() override { rclcpp::shutdown(); } }; @@ -90,17 +90,17 @@ TEST_F(VectorMapBasedRuleMockNode, vectorMapBasedRule) { shared_data_->localization_pose_cov.set_and_invoke(create_pose(5, 5)); auto ret = rule_->update(); - EXPECT_TRUE(ret.at(pose_estimator_arbiter::PoseEstimatorType::ndt)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::yabloc)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::eagleye)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::artag)); + EXPECT_TRUE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::ndt)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::yabloc)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::eagleye)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::artag)); } { shared_data_->localization_pose_cov.set_and_invoke(create_pose(15, 15)); auto ret = rule_->update(); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::ndt)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::yabloc)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::eagleye)); - EXPECT_FALSE(ret.at(pose_estimator_arbiter::PoseEstimatorType::artag)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::ndt)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::yabloc)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::eagleye)); + EXPECT_FALSE(ret.at(autoware::pose_estimator_arbiter::PoseEstimatorType::artag)); } } diff --git a/localization/pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml b/localization/autoware_pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml similarity index 93% rename from localization/pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml rename to localization/autoware_pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml index b5be96fc3ce44..d38f0e2a104a8 100644 --- a/localization/pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml +++ b/localization/autoware_pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/localization/pose_estimator_arbiter/media/architecture.drawio.svg b/localization/autoware_pose_estimator_arbiter/media/architecture.drawio.svg similarity index 100% rename from localization/pose_estimator_arbiter/media/architecture.drawio.svg rename to localization/autoware_pose_estimator_arbiter/media/architecture.drawio.svg diff --git a/localization/pose_estimator_arbiter/media/pcd_occupancy.drawio.svg b/localization/autoware_pose_estimator_arbiter/media/pcd_occupancy.drawio.svg similarity index 100% rename from localization/pose_estimator_arbiter/media/pcd_occupancy.drawio.svg rename to localization/autoware_pose_estimator_arbiter/media/pcd_occupancy.drawio.svg diff --git a/localization/pose_estimator_arbiter/media/pose_estimator_area_in_vector_map.png b/localization/autoware_pose_estimator_arbiter/media/pose_estimator_area_in_vector_map.png similarity index 100% rename from localization/pose_estimator_arbiter/media/pose_estimator_area_in_vector_map.png rename to localization/autoware_pose_estimator_arbiter/media/pose_estimator_area_in_vector_map.png diff --git a/localization/pose_estimator_arbiter/media/single_pose_estimator.drawio.svg b/localization/autoware_pose_estimator_arbiter/media/single_pose_estimator.drawio.svg similarity index 100% rename from localization/pose_estimator_arbiter/media/single_pose_estimator.drawio.svg rename to localization/autoware_pose_estimator_arbiter/media/single_pose_estimator.drawio.svg diff --git a/localization/pose_estimator_arbiter/package.xml b/localization/autoware_pose_estimator_arbiter/package.xml similarity index 97% rename from localization/pose_estimator_arbiter/package.xml rename to localization/autoware_pose_estimator_arbiter/package.xml index d97c9f15fc8ae..f3aa30a2c6425 100644 --- a/localization/pose_estimator_arbiter/package.xml +++ b/localization/autoware_pose_estimator_arbiter/package.xml @@ -1,7 +1,7 @@ - pose_estimator_arbiter + autoware_pose_estimator_arbiter 0.1.0 The arbiter of multiple pose estimators Yamato Ando diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter.hpp similarity index 89% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp rename to localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter.hpp index 013b4b38f9ef6..b70ab378eac67 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__POSE_ESTIMATOR_ARBITER_HPP_ -#define POSE_ESTIMATOR_ARBITER__POSE_ESTIMATOR_ARBITER_HPP_ +#ifndef POSE_ESTIMATOR_ARBITER_HPP_ +#define POSE_ESTIMATOR_ARBITER_HPP_ -#include "pose_estimator_arbiter/shared_data.hpp" -#include "pose_estimator_arbiter/stopper/base_stopper.hpp" -#include "pose_estimator_arbiter/switch_rule/base_switch_rule.hpp" +#include "shared_data.hpp" +#include "stopper/base_stopper.hpp" +#include "switch_rule/base_switch_rule.hpp" #include #include @@ -32,7 +32,7 @@ #include #include -namespace pose_estimator_arbiter +namespace autoware::pose_estimator_arbiter { class PoseEstimatorArbiter : public rclcpp::Node { @@ -95,6 +95,6 @@ class PoseEstimatorArbiter : public rclcpp::Node // Timer callback void on_timer(); }; -} // namespace pose_estimator_arbiter +} // namespace autoware::pose_estimator_arbiter -#endif // POSE_ESTIMATOR_ARBITER__POSE_ESTIMATOR_ARBITER_HPP_ +#endif // POSE_ESTIMATOR_ARBITER_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter_core.cpp similarity index 90% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp rename to localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter_core.cpp index 8e25628d6e0fc..9108d44e82fb5 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp +++ b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter_core.cpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/pose_estimator_arbiter.hpp" -#include "pose_estimator_arbiter/pose_estimator_type.hpp" -#include "pose_estimator_arbiter/stopper/stopper_artag.hpp" -#include "pose_estimator_arbiter/stopper/stopper_eagleye.hpp" -#include "pose_estimator_arbiter/stopper/stopper_ndt.hpp" -#include "pose_estimator_arbiter/stopper/stopper_yabloc.hpp" -#include "pose_estimator_arbiter/switch_rule/enable_all_rule.hpp" +#include "pose_estimator_arbiter.hpp" +#include "pose_estimator_type.hpp" +#include "stopper/stopper_artag.hpp" +#include "stopper/stopper_eagleye.hpp" +#include "stopper/stopper_ndt.hpp" +#include "stopper/stopper_yabloc.hpp" +#include "switch_rule/enable_all_rule.hpp" #include -namespace pose_estimator_arbiter +namespace autoware::pose_estimator_arbiter { // Parses ros param to get the estimator set that is running static std::unordered_set parse_estimator_name_args( @@ -111,9 +111,9 @@ PoseEstimatorArbiter::PoseEstimatorArbiter(const rclcpp::NodeOptions & options) load_switch_rule(); // Timer callback - auto on_timer = std::bind(&PoseEstimatorArbiter::on_timer, this); - timer_ = - rclcpp::create_timer(this, this->get_clock(), rclcpp::Rate(1).period(), std::move(on_timer)); + auto on_timer_callback = std::bind(&PoseEstimatorArbiter::on_timer, this); + timer_ = rclcpp::create_timer( + this, this->get_clock(), rclcpp::Rate(1).period(), std::move(on_timer_callback)); // Enable all pose estimators at the first toggle_all(true); @@ -210,7 +210,7 @@ void PoseEstimatorArbiter::on_timer() publish_diagnostics(); } -} // namespace pose_estimator_arbiter +} // namespace autoware::pose_estimator_arbiter #include -RCLCPP_COMPONENTS_REGISTER_NODE(pose_estimator_arbiter::PoseEstimatorArbiter) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pose_estimator_arbiter::PoseEstimatorArbiter) diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_type.hpp b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_type.hpp similarity index 73% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_type.hpp rename to localization/autoware_pose_estimator_arbiter/src/pose_estimator_type.hpp index d78bfeb05b4f0..98f92612f8bc7 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_type.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_type.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__POSE_ESTIMATOR_TYPE_HPP_ -#define POSE_ESTIMATOR_ARBITER__POSE_ESTIMATOR_TYPE_HPP_ +#ifndef POSE_ESTIMATOR_TYPE_HPP_ +#define POSE_ESTIMATOR_TYPE_HPP_ -namespace pose_estimator_arbiter +namespace autoware::pose_estimator_arbiter { enum class PoseEstimatorType : int { ndt = 1, yabloc = 2, eagleye = 4, artag = 8 }; -} // namespace pose_estimator_arbiter +} // namespace autoware::pose_estimator_arbiter -#endif // POSE_ESTIMATOR_ARBITER__POSE_ESTIMATOR_TYPE_HPP_ +#endif // POSE_ESTIMATOR_TYPE_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/shared_data.hpp b/localization/autoware_pose_estimator_arbiter/src/shared_data.hpp similarity index 93% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/shared_data.hpp rename to localization/autoware_pose_estimator_arbiter/src/shared_data.hpp index 0d3dbfab11cbe..6332b77a9ed31 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/shared_data.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/shared_data.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__SHARED_DATA_HPP_ -#define POSE_ESTIMATOR_ARBITER__SHARED_DATA_HPP_ +#ifndef SHARED_DATA_HPP_ +#define SHARED_DATA_HPP_ #include #include @@ -25,7 +25,7 @@ #include #include -namespace pose_estimator_arbiter +namespace autoware::pose_estimator_arbiter { template struct CallbackInvokingVariable @@ -97,5 +97,5 @@ struct SharedData InitializationState{}.set__state(InitializationState::UNINITIALIZED))}; }; -} // namespace pose_estimator_arbiter -#endif // POSE_ESTIMATOR_ARBITER__SHARED_DATA_HPP_ +} // namespace autoware::pose_estimator_arbiter +#endif // SHARED_DATA_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/base_stopper.hpp b/localization/autoware_pose_estimator_arbiter/src/stopper/base_stopper.hpp similarity index 81% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/base_stopper.hpp rename to localization/autoware_pose_estimator_arbiter/src/stopper/base_stopper.hpp index d64592a12308e..8b47b0e3b3a9a 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/base_stopper.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/stopper/base_stopper.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__STOPPER__BASE_STOPPER_HPP_ -#define POSE_ESTIMATOR_ARBITER__STOPPER__BASE_STOPPER_HPP_ +#ifndef STOPPER__BASE_STOPPER_HPP_ +#define STOPPER__BASE_STOPPER_HPP_ -#include "pose_estimator_arbiter/shared_data.hpp" +#include "shared_data.hpp" #include #include #include -namespace pose_estimator_arbiter::stopper +namespace autoware::pose_estimator_arbiter::stopper { class BaseStopper { @@ -48,6 +48,6 @@ class BaseStopper rclcpp::Logger logger_; std::shared_ptr shared_data_{nullptr}; }; -} // namespace pose_estimator_arbiter::stopper +} // namespace autoware::pose_estimator_arbiter::stopper -#endif // POSE_ESTIMATOR_ARBITER__STOPPER__BASE_STOPPER_HPP_ +#endif // STOPPER__BASE_STOPPER_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_artag.hpp b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_artag.hpp similarity index 82% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_artag.hpp rename to localization/autoware_pose_estimator_arbiter/src/stopper/stopper_artag.hpp index f334983f33aad..3635ebd39c545 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_artag.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_artag.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_ARTAG_HPP_ -#define POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_ARTAG_HPP_ +#ifndef STOPPER__STOPPER_ARTAG_HPP_ +#define STOPPER__STOPPER_ARTAG_HPP_ -#include "pose_estimator_arbiter/stopper/base_stopper.hpp" +#include "stopper/base_stopper.hpp" #include #include #include -namespace pose_estimator_arbiter::stopper +namespace autoware::pose_estimator_arbiter::stopper { class StopperArTag : public BaseStopper { @@ -52,6 +52,6 @@ class StopperArTag : public BaseStopper bool ar_tag_is_enabled_; rclcpp::Publisher::SharedPtr pub_image_; }; -} // namespace pose_estimator_arbiter::stopper +} // namespace autoware::pose_estimator_arbiter::stopper -#endif // POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_ARTAG_HPP_ +#endif // STOPPER__STOPPER_ARTAG_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_eagleye.hpp b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_eagleye.hpp similarity index 81% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_eagleye.hpp rename to localization/autoware_pose_estimator_arbiter/src/stopper/stopper_eagleye.hpp index cc800ad6bdee4..cfddf3e13014f 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_eagleye.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_eagleye.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_EAGLEYE_HPP_ -#define POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_EAGLEYE_HPP_ -#include "pose_estimator_arbiter/stopper/base_stopper.hpp" +#ifndef STOPPER__STOPPER_EAGLEYE_HPP_ +#define STOPPER__STOPPER_EAGLEYE_HPP_ +#include "stopper/base_stopper.hpp" #include #include -namespace pose_estimator_arbiter::stopper +namespace autoware::pose_estimator_arbiter::stopper { class StopperEagleye : public BaseStopper { @@ -49,6 +49,6 @@ class StopperEagleye : public BaseStopper bool eagleye_is_enabled_; rclcpp::Publisher::SharedPtr pub_pose_; }; -} // namespace pose_estimator_arbiter::stopper +} // namespace autoware::pose_estimator_arbiter::stopper -#endif // POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_EAGLEYE_HPP_ +#endif // STOPPER__STOPPER_EAGLEYE_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_ndt.hpp b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_ndt.hpp similarity index 81% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_ndt.hpp rename to localization/autoware_pose_estimator_arbiter/src/stopper/stopper_ndt.hpp index 3b7c083ea31e3..eba43118c7860 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_ndt.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_ndt.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_NDT_HPP_ -#define POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_NDT_HPP_ -#include "pose_estimator_arbiter/stopper/base_stopper.hpp" +#ifndef STOPPER__STOPPER_NDT_HPP_ +#define STOPPER__STOPPER_NDT_HPP_ +#include "stopper/base_stopper.hpp" #include #include -namespace pose_estimator_arbiter::stopper +namespace autoware::pose_estimator_arbiter::stopper { class StopperNdt : public BaseStopper { @@ -49,6 +49,6 @@ class StopperNdt : public BaseStopper rclcpp::Publisher::SharedPtr pub_pointcloud_; bool ndt_is_enabled_; }; -} // namespace pose_estimator_arbiter::stopper +} // namespace autoware::pose_estimator_arbiter::stopper -#endif // POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_NDT_HPP_ +#endif // STOPPER__STOPPER_NDT_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_yabloc.hpp b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_yabloc.hpp similarity index 89% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_yabloc.hpp rename to localization/autoware_pose_estimator_arbiter/src/stopper/stopper_yabloc.hpp index 808a5bf9407ca..77aa9603ac06a 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/stopper/stopper_yabloc.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/stopper/stopper_yabloc.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_YABLOC_HPP_ -#define POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_YABLOC_HPP_ -#include "pose_estimator_arbiter/stopper/base_stopper.hpp" +#ifndef STOPPER__STOPPER_YABLOC_HPP_ +#define STOPPER__STOPPER_YABLOC_HPP_ +#include "stopper/base_stopper.hpp" #include #include #include -namespace pose_estimator_arbiter::stopper +namespace autoware::pose_estimator_arbiter::stopper { class StopperYabLoc : public BaseStopper { @@ -86,5 +86,5 @@ class StopperYabLoc : public BaseStopper rclcpp::Client::SharedPtr enable_service_client_; rclcpp::Publisher::SharedPtr pub_image_; }; -} // namespace pose_estimator_arbiter::stopper -#endif // POSE_ESTIMATOR_ARBITER__STOPPER__STOPPER_YABLOC_HPP_ +} // namespace autoware::pose_estimator_arbiter::stopper +#endif // STOPPER__STOPPER_YABLOC_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/base_switch_rule.hpp b/localization/autoware_pose_estimator_arbiter/src/switch_rule/base_switch_rule.hpp similarity index 78% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/base_switch_rule.hpp rename to localization/autoware_pose_estimator_arbiter/src/switch_rule/base_switch_rule.hpp index 95d10c2b741a8..0462ce6e7d340 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/base_switch_rule.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/switch_rule/base_switch_rule.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__SWITCH_RULE__BASE_SWITCH_RULE_HPP_ -#define POSE_ESTIMATOR_ARBITER__SWITCH_RULE__BASE_SWITCH_RULE_HPP_ +#ifndef SWITCH_RULE__BASE_SWITCH_RULE_HPP_ +#define SWITCH_RULE__BASE_SWITCH_RULE_HPP_ -#include "pose_estimator_arbiter/pose_estimator_type.hpp" +#include "pose_estimator_type.hpp" #include @@ -26,7 +26,7 @@ #include #include -namespace pose_estimator_arbiter::switch_rule +namespace autoware::pose_estimator_arbiter::switch_rule { class BaseSwitchRule { @@ -44,7 +44,8 @@ class BaseSwitchRule BaseSwitchRule(BaseSwitchRule && other) noexcept = default; BaseSwitchRule & operator=(const BaseSwitchRule & other) = default; BaseSwitchRule & operator=(BaseSwitchRule && other) noexcept = default; - virtual std::unordered_map update() = 0; + virtual std::unordered_map + update() = 0; virtual std::string debug_string() { return std::string{}; } virtual MarkerArray debug_marker_array() { return MarkerArray{}; } @@ -53,6 +54,6 @@ class BaseSwitchRule std::shared_ptr logger_ptr_{nullptr}; }; -} // namespace pose_estimator_arbiter::switch_rule +} // namespace autoware::pose_estimator_arbiter::switch_rule -#endif // POSE_ESTIMATOR_ARBITER__SWITCH_RULE__BASE_SWITCH_RULE_HPP_ +#endif // SWITCH_RULE__BASE_SWITCH_RULE_HPP_ diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp b/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.cpp similarity index 88% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp rename to localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.cpp index aebad094a0eca..9767e9ef4fba4 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/switch_rule/enable_all_rule.hpp" +#include "switch_rule/enable_all_rule.hpp" #include @@ -22,7 +22,7 @@ #include #include -namespace pose_estimator_arbiter::switch_rule +namespace autoware::pose_estimator_arbiter::switch_rule { EnableAllRule::EnableAllRule( rclcpp::Node & node, std::unordered_set running_estimator_list, @@ -41,4 +41,4 @@ std::unordered_map EnableAllRule::update() }; } -} // namespace pose_estimator_arbiter::switch_rule +} // namespace autoware::pose_estimator_arbiter::switch_rule diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.hpp b/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.hpp similarity index 71% rename from localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.hpp rename to localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.hpp index 63142b0e662e1..bf2aa68df35d5 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/switch_rule/enable_all_rule.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_ESTIMATOR_ARBITER__SWITCH_RULE__ENABLE_ALL_RULE_HPP_ -#define POSE_ESTIMATOR_ARBITER__SWITCH_RULE__ENABLE_ALL_RULE_HPP_ +#ifndef SWITCH_RULE__ENABLE_ALL_RULE_HPP_ +#define SWITCH_RULE__ENABLE_ALL_RULE_HPP_ -#include "pose_estimator_arbiter/shared_data.hpp" -#include "pose_estimator_arbiter/switch_rule/base_switch_rule.hpp" +#include "shared_data.hpp" +#include "switch_rule/base_switch_rule.hpp" #include #include #include #include -namespace pose_estimator_arbiter::switch_rule +namespace autoware::pose_estimator_arbiter::switch_rule { class EnableAllRule : public BaseSwitchRule { @@ -38,6 +38,6 @@ class EnableAllRule : public BaseSwitchRule const std::unordered_set running_estimator_list_; }; -} // namespace pose_estimator_arbiter::switch_rule +} // namespace autoware::pose_estimator_arbiter::switch_rule -#endif // POSE_ESTIMATOR_ARBITER__SWITCH_RULE__ENABLE_ALL_RULE_HPP_ +#endif // SWITCH_RULE__ENABLE_ALL_RULE_HPP_ diff --git a/localization/pose_estimator_arbiter/test/test_pose_estimator_arbiter.py b/localization/autoware_pose_estimator_arbiter/test/test_pose_estimator_arbiter.py similarity index 98% rename from localization/pose_estimator_arbiter/test/test_pose_estimator_arbiter.py rename to localization/autoware_pose_estimator_arbiter/test/test_pose_estimator_arbiter.py index c419fb68e0571..a5ff04c002004 100644 --- a/localization/pose_estimator_arbiter/test/test_pose_estimator_arbiter.py +++ b/localization/autoware_pose_estimator_arbiter/test/test_pose_estimator_arbiter.py @@ -38,7 +38,7 @@ @pytest.mark.launch_test def generate_test_description(): test_pose_estimator_arbiter_launch_file = os.path.join( - get_package_share_directory("pose_estimator_arbiter"), + get_package_share_directory("autoware_pose_estimator_arbiter"), "launch", "pose_estimator_arbiter.launch.xml", ) diff --git a/localization/pose_estimator_arbiter/test/test_shared_data.cpp b/localization/autoware_pose_estimator_arbiter/test/test_shared_data.cpp similarity index 90% rename from localization/pose_estimator_arbiter/test/test_shared_data.cpp rename to localization/autoware_pose_estimator_arbiter/test/test_shared_data.cpp index 3c1fa50b502a1..c0f7044442d71 100644 --- a/localization/pose_estimator_arbiter/test/test_shared_data.cpp +++ b/localization/autoware_pose_estimator_arbiter/test/test_shared_data.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pose_estimator_arbiter/shared_data.hpp" +#include "shared_data.hpp" #include TEST(SharedData, callback_invoked_correctly) { - pose_estimator_arbiter::CallbackInvokingVariable variable; + autoware::pose_estimator_arbiter::CallbackInvokingVariable variable; // register callback bool callback_invoked = false; @@ -44,7 +44,7 @@ TEST(SharedData, callback_invoked_correctly) TEST(SharedData, multiple_callback_invoked_correctly) { - pose_estimator_arbiter::CallbackInvokingVariable variable; + autoware::pose_estimator_arbiter::CallbackInvokingVariable variable; // register callback int callback_invoked_num = 0;