diff --git a/common/.pages b/common/.pages index 38cffcb1dc027..7d17018e2762b 100644 --- a/common/.pages +++ b/common/.pages @@ -3,6 +3,7 @@ nav: - 'Testing Libraries': - 'autoware_testing': common/autoware_testing/design/autoware_testing-design - 'fake_test_node': common/fake_test_node/design/fake_test_node-design + - 'Test Utils': common/autoware_test_utils - 'Common Libraries': - 'autoware_auto_common': - 'comparisons': common/autoware_auto_common/design/comparisons diff --git a/planning/planning_test_utils/CMakeLists.txt b/common/autoware_test_utils/CMakeLists.txt similarity index 81% rename from planning/planning_test_utils/CMakeLists.txt rename to common/autoware_test_utils/CMakeLists.txt index ce746352bb89c..91adf935445b4 100644 --- a/planning/planning_test_utils/CMakeLists.txt +++ b/common/autoware_test_utils/CMakeLists.txt @@ -1,11 +1,11 @@ cmake_minimum_required(VERSION 3.14) -project(planning_test_utils) +project(autoware_test_utils) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(planning_test_utils SHARED - src/planning_test_utils.cpp) +ament_auto_add_library(autoware_test_utils SHARED + src/autoware_test_utils.cpp) ament_auto_add_library(mock_data_parser SHARED src/mock_data_parser.cpp) diff --git a/planning/planning_test_utils/README.md b/common/autoware_test_utils/README.md similarity index 96% rename from planning/planning_test_utils/README.md rename to common/autoware_test_utils/README.md index c064e5791a487..a656f35a90ce4 100644 --- a/planning/planning_test_utils/README.md +++ b/common/autoware_test_utils/README.md @@ -15,7 +15,7 @@ The objective of the `test_utils` is to develop a unit testing library for the A ## Available Maps -The following maps are available [here](https://github.com/autowarefoundation/autoware.universe/tree/main/planning/planning_test_utils/test_map) +The following maps are available [here](https://github.com/autowarefoundation/autoware.universe/tree/main/planning/autoware_test_utils/test_map) ### Common diff --git a/planning/planning_test_utils/config/path_with_lane_id_data.yaml b/common/autoware_test_utils/config/path_with_lane_id_data.yaml similarity index 100% rename from planning/planning_test_utils/config/path_with_lane_id_data.yaml rename to common/autoware_test_utils/config/path_with_lane_id_data.yaml diff --git a/planning/planning_test_utils/config/test_common.param.yaml b/common/autoware_test_utils/config/test_common.param.yaml similarity index 100% rename from planning/planning_test_utils/config/test_common.param.yaml rename to common/autoware_test_utils/config/test_common.param.yaml diff --git a/planning/planning_test_utils/config/test_nearest_search.param.yaml b/common/autoware_test_utils/config/test_nearest_search.param.yaml similarity index 100% rename from planning/planning_test_utils/config/test_nearest_search.param.yaml rename to common/autoware_test_utils/config/test_nearest_search.param.yaml diff --git a/planning/planning_test_utils/config/test_vehicle_info.param.yaml b/common/autoware_test_utils/config/test_vehicle_info.param.yaml similarity index 100% rename from planning/planning_test_utils/config/test_vehicle_info.param.yaml rename to common/autoware_test_utils/config/test_vehicle_info.param.yaml diff --git a/planning/planning_test_utils/images/2km-test.png b/common/autoware_test_utils/images/2km-test.png similarity index 100% rename from planning/planning_test_utils/images/2km-test.png rename to common/autoware_test_utils/images/2km-test.png diff --git a/planning/planning_test_utils/images/2km-test.svg b/common/autoware_test_utils/images/2km-test.svg similarity index 100% rename from planning/planning_test_utils/images/2km-test.svg rename to common/autoware_test_utils/images/2km-test.svg diff --git a/planning/planning_test_utils/images/common.png b/common/autoware_test_utils/images/common.png similarity index 100% rename from planning/planning_test_utils/images/common.png rename to common/autoware_test_utils/images/common.png diff --git a/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp similarity index 97% rename from planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp rename to common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp index 9d787070a9dc5..6b77bb4c24931 100644 --- a/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_TEST_UTILS__PLANNING_TEST_UTILS_HPP_ -#define PLANNING_TEST_UTILS__PLANNING_TEST_UTILS_HPP_ +#ifndef AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_ +#define AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_ #include "ament_index_cpp/get_package_share_directory.hpp" #include "rclcpp/rclcpp.hpp" @@ -54,7 +54,7 @@ #include #include -namespace test_utils +namespace autoware::test_utils { using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_map_msgs::msg::LaneletMapBin; @@ -191,7 +191,7 @@ LaneletMapBin make_map_bin_msg( * @brief Creates a LaneletMapBin message using a predefined Lanelet2 map file. * * This function loads a lanelet2_map.osm from the test_map folder in the - * planning_test_utils package, overwrites the centerline with a resolution of 5.0, + * autoware_test_utils package, overwrites the centerline with a resolution of 5.0, * and converts the map to a LaneletMapBin message. * * @return A LaneletMapBin message containing the map data. @@ -299,7 +299,7 @@ void updateNodeOptions( * @brief Loads a PathWithLaneId message from a YAML file. * * This function loads a PathWithLaneId message from a YAML file located in the - * planning_test_utils package. + * autoware_test_utils package. * * @return A PathWithLaneId message containing the loaded data. */ @@ -468,15 +468,15 @@ void publishToTargetNode( throw std::runtime_error(std::string("Topic name for ") + typeid(data).name() + " is empty"); } - test_utils::setPublisher(test_node, topic_name, publisher); + autoware::test_utils::setPublisher(test_node, topic_name, publisher); publisher->publish(data); if (target_node->count_subscribers(topic_name) == 0) { throw std::runtime_error("No subscriber for " + topic_name); } - test_utils::spinSomeNodes(test_node, target_node, repeat_count); + autoware::test_utils::spinSomeNodes(test_node, target_node, repeat_count); } -} // namespace test_utils +} // namespace autoware::test_utils -#endif // PLANNING_TEST_UTILS__PLANNING_TEST_UTILS_HPP_ +#endif // AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_ diff --git a/planning/planning_test_utils/include/planning_test_utils/mock_data_parser.hpp b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp similarity index 86% rename from planning/planning_test_utils/include/planning_test_utils/mock_data_parser.hpp rename to common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp index 09d4474dda15d..47284da447133 100644 --- a/planning/planning_test_utils/include/planning_test_utils/mock_data_parser.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_TEST_UTILS__MOCK_DATA_PARSER_HPP_ -#define PLANNING_TEST_UTILS__MOCK_DATA_PARSER_HPP_ +#ifndef AUTOWARE_TEST_UTILS__MOCK_DATA_PARSER_HPP_ +#define AUTOWARE_TEST_UTILS__MOCK_DATA_PARSER_HPP_ #include #include @@ -25,7 +25,7 @@ #include #include -namespace test_utils +namespace autoware::test_utils { using autoware_planning_msgs::msg::LaneletPrimitive; using autoware_planning_msgs::msg::LaneletRoute; @@ -41,6 +41,6 @@ std::vector parse_lanelet_primitives(const YAML::Node & node); std::vector parse_segments(const YAML::Node & node); LaneletRoute parse_lanelet_route_file(const std::string & filename); -} // namespace test_utils +} // namespace autoware::test_utils -#endif // PLANNING_TEST_UTILS__MOCK_DATA_PARSER_HPP_ +#endif // AUTOWARE_TEST_UTILS__MOCK_DATA_PARSER_HPP_ diff --git a/planning/planning_test_utils/package.xml b/common/autoware_test_utils/package.xml similarity index 98% rename from planning/planning_test_utils/package.xml rename to common/autoware_test_utils/package.xml index 8f3c3259c33d0..555345c1d9105 100644 --- a/planning/planning_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -1,7 +1,7 @@ - planning_test_utils + autoware_test_utils 0.1.0 ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara diff --git a/planning/planning_test_utils/src/planning_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp similarity index 94% rename from planning/planning_test_utils/src/planning_test_utils.cpp rename to common/autoware_test_utils/src/autoware_test_utils.cpp index 3ba97552ef250..c7435be5afcec 100644 --- a/planning/planning_test_utils/src/planning_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_test_utils/planning_test_utils.hpp" -namespace test_utils +#include "autoware_test_utils/autoware_test_utils.hpp" +namespace autoware::test_utils { geometry_msgs::msg::Pose createPose( @@ -122,9 +122,9 @@ LaneletMapBin make_map_bin_msg( LaneletMapBin makeMapBinMsg() { - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto lanelet2_path = planning_test_utils_dir + "/test_map/lanelet2_map.osm"; + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); + const auto lanelet2_path = autoware_test_utils_dir + "/test_map/lanelet2_map.osm"; double center_line_resolution = 5.0; return make_map_bin_msg(lanelet2_path, center_line_resolution); @@ -147,7 +147,7 @@ Odometry makeInitialPose(const double shift) const auto shift_y = shift * std::cos(yaw); const std::array start_pose{ 3722.16015625 + shift_x, 73723.515625 + shift_y, 0.233112560494183, yaw}; - current_odometry.pose.pose = test_utils::createPose(start_pose); + current_odometry.pose.pose = autoware::test_utils::createPose(start_pose); current_odometry.header.frame_id = "map"; return current_odometry; } @@ -251,9 +251,9 @@ void updateNodeOptions( PathWithLaneId loadPathWithLaneIdInYaml() { - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto yaml_path = planning_test_utils_dir + "/config/path_with_lane_id_data.yaml"; + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); + const auto yaml_path = autoware_test_utils_dir + "/config/path_with_lane_id_data.yaml"; YAML::Node yaml_node = YAML::LoadFile(yaml_path); PathWithLaneId path_msg; @@ -311,4 +311,4 @@ PathWithLaneId loadPathWithLaneIdInYaml() return path_msg; } -} // namespace test_utils +} // namespace autoware::test_utils diff --git a/planning/planning_test_utils/src/mock_data_parser.cpp b/common/autoware_test_utils/src/mock_data_parser.cpp similarity index 94% rename from planning/planning_test_utils/src/mock_data_parser.cpp rename to common/autoware_test_utils/src/mock_data_parser.cpp index f9f9a7b0b1594..a8f2a8c6433df 100644 --- a/planning/planning_test_utils/src/mock_data_parser.cpp +++ b/common/autoware_test_utils/src/mock_data_parser.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_test_utils/mock_data_parser.hpp" +#include "autoware_test_utils/mock_data_parser.hpp" #include @@ -27,7 +27,7 @@ #include #include -namespace test_utils +namespace autoware::test_utils { Pose parse_pose(const YAML::Node & node) { @@ -85,8 +85,8 @@ LaneletRoute parse_lanelet_route_file(const std::string & filename) lanelet_route.goal_pose = (config["goal_pose"]) ? parse_pose(config["goal_pose"]) : Pose(); lanelet_route.segments = parse_segments(config["segments"]); } catch (const std::exception & e) { - RCLCPP_DEBUG(rclcpp::get_logger("planning_test_utils"), "Exception caught: %s", e.what()); + RCLCPP_DEBUG(rclcpp::get_logger("autoware_test_utils"), "Exception caught: %s", e.what()); } return lanelet_route; } -} // namespace test_utils +} // namespace autoware::test_utils diff --git a/planning/planning_test_utils/test/test_mock_data_parser.cpp b/common/autoware_test_utils/test/test_mock_data_parser.cpp similarity index 94% rename from planning/planning_test_utils/test/test_mock_data_parser.cpp rename to common/autoware_test_utils/test/test_mock_data_parser.cpp index cda09522d8e6e..f9e37a521c42c 100644 --- a/planning/planning_test_utils/test/test_mock_data_parser.cpp +++ b/common/autoware_test_utils/test/test_mock_data_parser.cpp @@ -16,9 +16,9 @@ // Assuming the parseRouteFile function is in 'RouteHandler.h' #include "ament_index_cpp/get_package_share_directory.hpp" -#include "planning_test_utils/mock_data_parser.hpp" +#include "autoware_test_utils/mock_data_parser.hpp" -namespace test_utils +namespace autoware::test_utils { // Example YAML structure as a string for testing const char g_complete_yaml[] = R"( @@ -94,10 +94,10 @@ TEST(ParseFunctions, CompleteYAMLTest) TEST(ParseFunction, CompleteFromFilename) { - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto parser_test_route = - planning_test_utils_dir + "/test_data/lanelet_route_parser_test.yaml"; + autoware_test_utils_dir + "/test_data/lanelet_route_parser_test.yaml"; const auto lanelet_route = parse_lanelet_route_file(parser_test_route); EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.x, 1.0); @@ -132,4 +132,4 @@ TEST(ParseFunction, CompleteFromFilename) EXPECT_EQ(segment1.primitives[3].id, 88); EXPECT_EQ(segment1.primitives[3].primitive_type, "lane"); } -} // namespace test_utils +} // namespace autoware::test_utils diff --git a/planning/planning_test_utils/test_data/lanelet_route_parser_test.yaml b/common/autoware_test_utils/test_data/lanelet_route_parser_test.yaml similarity index 100% rename from planning/planning_test_utils/test_data/lanelet_route_parser_test.yaml rename to common/autoware_test_utils/test_data/lanelet_route_parser_test.yaml diff --git a/planning/planning_test_utils/test_map/2km_test.osm b/common/autoware_test_utils/test_map/2km_test.osm similarity index 100% rename from planning/planning_test_utils/test_map/2km_test.osm rename to common/autoware_test_utils/test_map/2km_test.osm diff --git a/planning/planning_test_utils/test_map/lanelet2_map.osm b/common/autoware_test_utils/test_map/lanelet2_map.osm similarity index 100% rename from planning/planning_test_utils/test_map/lanelet2_map.osm rename to common/autoware_test_utils/test_map/lanelet2_map.osm diff --git a/planning/planning_test_utils/test_map/pointcloud_map.pcd b/common/autoware_test_utils/test_map/pointcloud_map.pcd similarity index 100% rename from planning/planning_test_utils/test_map/pointcloud_map.pcd rename to common/autoware_test_utils/test_map/pointcloud_map.pcd diff --git a/planning/.pages b/planning/.pages index ac13a5a66fcfd..cb537399a97af 100644 --- a/planning/.pages +++ b/planning/.pages @@ -83,7 +83,6 @@ nav: - 'Planning Debug Tools': - 'About Planning Debug Tools': https://github.com/autowarefoundation/autoware_tools/tree/main/planning/planning_debug_tools - 'Stop Reason Visualizer': https://github.com/autowarefoundation/autoware_tools/blob/main/planning/planning_debug_tools/doc-stop-reason-visualizer.md - - 'Planning Test Utils': planning/planning_test_utils - 'Planning Test Manager': planning/autoware_planning_test_manager - 'Planning Topic Converter': planning/autoware_planning_topic_converter - 'Planning Validator': planning/autoware_planning_validator diff --git a/planning/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 827221e4931b1..a34c2ed22004c 100644 --- a/planning/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -24,7 +24,7 @@ #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -44,10 +44,10 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_path_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); const auto behavior_path_lane_change_module_dir = ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module"); @@ -58,10 +58,10 @@ std::shared_ptr generateNode() params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( - node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware::test_utils::updateNodeOptions( + node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", diff --git a/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 91b0f4c9df9f5..611a796507f44 100644 --- a/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -16,12 +16,12 @@ #include #include -#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -41,10 +41,10 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_path_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); std::vector module_names; module_names.emplace_back("autoware::behavior_path_planner::DynamicAvoidanceModuleManager"); @@ -53,10 +53,10 @@ std::shared_ptr generateNode() params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( - node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware::test_utils::updateNodeOptions( + node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", diff --git a/planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 642e4d7fc6a30..12db2d1115efc 100644 --- a/planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -15,7 +15,7 @@ #include "ament_index_cpp/get_package_share_directory.hpp" #include "autoware_behavior_path_planner/behavior_path_planner_node.hpp" #include "autoware_planning_test_manager/autoware_planning_test_manager.hpp" -#include "planning_test_utils/planning_test_utils.hpp" +#include "autoware_test_utils/autoware_test_utils.hpp" #include @@ -23,7 +23,7 @@ #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -43,10 +43,10 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_path_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); const auto behavior_path_lane_change_module_dir = ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module"); @@ -60,11 +60,11 @@ std::shared_ptr generateNode() params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( + autoware::test_utils::updateNodeOptions( node_options, { - planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", diff --git a/planning/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 2dd5bb2c55063..3d6987e66e07f 100644 --- a/planning/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -15,7 +15,7 @@ #include "ament_index_cpp/get_package_share_directory.hpp" #include "autoware_behavior_path_planner/behavior_path_planner_node.hpp" #include "autoware_planning_test_manager/autoware_planning_test_manager.hpp" -#include "planning_test_utils/planning_test_utils.hpp" +#include "autoware_test_utils/autoware_test_utils.hpp" #include @@ -23,7 +23,7 @@ #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -43,10 +43,10 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_path_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); const auto behavior_path_lane_change_module_dir = ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module"); @@ -58,10 +58,10 @@ std::shared_ptr generateNode() params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( - node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware::test_utils::updateNodeOptions( + node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", diff --git a/planning/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp index 5422bffa2094a..e70187754599a 100644 --- a/planning/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -24,7 +24,7 @@ #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -44,10 +44,10 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_path_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); std::vector module_names; @@ -55,10 +55,10 @@ std::shared_ptr generateNode() params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( - node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware::test_utils::updateNodeOptions( + node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml"}); diff --git a/planning/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp index 266054e9d46f2..fecafe1a8680b 100644 --- a/planning/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -24,7 +24,7 @@ #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -44,10 +44,10 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_path_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); std::vector module_names; module_names.emplace_back("autoware::behavior_path_planner::SideShiftModuleManager"); @@ -56,11 +56,11 @@ std::shared_ptr generateNode() params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( + autoware::test_utils::updateNodeOptions( node_options, - {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 95512fbffa575..7aa5b67b23d34 100644 --- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -16,12 +16,12 @@ #include #include -#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -41,10 +41,10 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_path_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); std::vector module_names; module_names.emplace_back( @@ -54,10 +54,10 @@ std::shared_ptr generateNode() params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( - node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware::test_utils::updateNodeOptions( + node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", diff --git a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index e630783f82d6b..113edb6fcf7b4 100644 --- a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -24,7 +24,7 @@ #include using autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -47,8 +47,8 @@ std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto behavior_velocity_planner_dir = ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner"); const auto velocity_smoother_dir = @@ -88,10 +88,10 @@ std::shared_ptr generateNode() params.emplace_back("is_simulation", false); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( - node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware::test_utils::updateNodeOptions( + node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml", velocity_smoother_dir + "/config/Analytical.param.yaml", behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml", @@ -100,7 +100,7 @@ std::shared_ptr generateNode() get_behavior_velocity_module_config("walkway"), get_behavior_velocity_module_config_no_prefix("detection_area"), get_behavior_velocity_module_config("intersection"), - get_behavior_velocity_module_config_no_prefix("no_stopping_area"), + get_behavior_velocity_module_config("no_stopping_area"), get_behavior_velocity_module_config("occlusion_spot"), get_behavior_velocity_module_config("run_out"), get_behavior_velocity_module_config_no_prefix("speed_bump"), diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp index 621bed12fdabc..319786dc722dd 100644 --- a/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp @@ -16,14 +16,14 @@ #include #include -#include +#include #include #include using autoware::freespace_planner::FreespacePlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -38,13 +38,13 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto freespace_planner_dir = ament_index_cpp::get_package_share_directory("autoware_freespace_planner"); node_options.arguments( {"--ros-args", "--params-file", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", freespace_planner_dir + "/config/freespace_planner.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp index 1c4f621649a4c..b28afba8b4895 100644 --- a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp @@ -16,14 +16,14 @@ #include #include -#include +#include #include #include using autoware::motion_planning::ObstacleCruisePlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -45,12 +45,12 @@ std::shared_ptr generateNode() auto node_options = rclcpp::NodeOptions{}; const auto obstacle_cruise_planner_dir = ament_index_cpp::get_package_share_directory("autoware_obstacle_cruise_planner"); - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); node_options.arguments( - {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", - "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + {"--ros-args", "--params-file", autoware_test_utils_dir + "/config/test_common.param.yaml", + "--params-file", autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + "--params-file", autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", obstacle_cruise_planner_dir + "/config/default_common.param.yaml", "--params-file", obstacle_cruise_planner_dir + "/config/obstacle_cruise_planner.param.yaml"}); diff --git a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp index 4af88539597be..8be7806c7e48a 100644 --- a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp +++ b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -26,20 +26,21 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) { rclcpp::init(0, nullptr); - auto test_manager = std::make_shared(); + auto test_manager = + std::make_shared(); auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto path_optimizer_dir = ament_index_cpp::get_package_share_directory("autoware_path_optimizer"); node_options.arguments( {"--ros-args", "--params-file", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", - planning_test_utils_dir + "/config/test_common.param.yaml", "--params-file", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", + autoware_test_utils_dir + "/config/test_common.param.yaml", "--params-file", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file", path_optimizer_dir + "/config/path_optimizer.param.yaml"}); auto test_target_node = std::make_shared(node_options); diff --git a/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp index 41c48630c8f8c..ed24c50325330 100644 --- a/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp +++ b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -26,18 +26,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) { rclcpp::init(0, nullptr); - auto test_manager = std::make_shared(); + auto test_manager = + std::make_shared(); auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto path_smoothing_dir = ament_index_cpp::get_package_share_directory("autoware_path_smoother"); node_options.arguments( - {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", - "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + {"--ros-args", "--params-file", autoware_test_utils_dir + "/config/test_common.param.yaml", + "--params-file", autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file", path_smoothing_dir + "/config/elastic_band_smoother.param.yaml"}); auto test_target_node = diff --git a/planning/autoware_planning_test_manager/README.md b/planning/autoware_planning_test_manager/README.md index 97eb2fd8d94fd..f4289d0d291a5 100644 --- a/planning/autoware_planning_test_manager/README.md +++ b/planning/autoware_planning_test_manager/README.md @@ -29,18 +29,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) rclcpp::init(0, nullptr); // instantiate test_manager with PlanningInterfaceTestManager type - auto test_manager = std::make_shared(); + auto test_manager = std::make_shared(); // get package directories for necessary configuration files - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto target_node_dir = ament_index_cpp::get_package_share_directory("target_node"); // set arguments to get the config file node_options.arguments( {"--ros-args", "--params-file", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", autoware_planning_validator_dir + "/config/planning_validator.param.yaml"}); // instantiate the TargetNode with node_options 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 08a6e1b9d6960..52c60a612d1bd 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 @@ -69,7 +69,7 @@ #include #include -namespace planning_test_utils +namespace autoware::planning_test_manager { using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_map_msgs::msg::LaneletMapBin; @@ -264,6 +264,6 @@ class PlanningInterfaceTestManager void publishAbnormalPath(rclcpp::Node::SharedPtr target_node, std::string topic_name); }; // class PlanningInterfaceTestManager -} // namespace planning_test_utils +} // namespace autoware::planning_test_manager #endif // AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_ diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp index 2f7116c162334..0e86740bd5b9a 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_ #define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_ #include -#include +#include #include #include @@ -34,7 +34,7 @@ using RouteSections = std::vector; Pose createPoseFromLaneID(const lanelet::Id & lane_id) { - auto map_bin_msg = test_utils::makeMapBinMsg(); + auto map_bin_msg = autoware::test_utils::makeMapBinMsg(); // create route_handler auto route_handler = std::make_shared(); route_handler->setMap(map_bin_msg); @@ -74,7 +74,7 @@ LaneletRoute makeBehaviorRouteFromLaneId(const int & start_lane_id, const int & route.start_pose = start_pose; route.goal_pose = goal_pose; - auto map_bin_msg = test_utils::makeMapBinMsg(); + auto map_bin_msg = autoware::test_utils::makeMapBinMsg(); // create route_handler auto route_handler = std::make_shared(); route_handler->setMap(map_bin_msg); @@ -97,7 +97,7 @@ LaneletRoute makeBehaviorRouteFromLaneId(const int & start_lane_id, const int & route_handler->setRouteLanelets(path_lanelets); const auto local_route_sections = route_handler->createMapSegments(path_lanelets); route_sections = - test_utils::combineConsecutiveRouteSections(route_sections, local_route_sections); + autoware::test_utils::combineConsecutiveRouteSections(route_sections, local_route_sections); for (const auto & route_section : route_sections) { for (const auto & primitive : route_section.primitives) { std::cerr << "primitive: " << primitive.id << std::endl; diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index ed47594295776..6ccebfc2f56fe 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -18,6 +18,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_route_handler + autoware_test_utils autoware_vehicle_msgs component_interface_specs component_interface_utils @@ -25,7 +26,6 @@ lanelet2_io motion_utils nav_msgs - planning_test_utils rclcpp tf2_msgs tf2_ros diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 01a8d89ca8b4d..715dc6277f419 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -16,10 +16,10 @@ #include #include -#include +#include #include -namespace planning_test_utils +namespace autoware::planning_test_manager { PlanningInterfaceTestManager::PlanningInterfaceTestManager() @@ -32,14 +32,14 @@ PlanningInterfaceTestManager::PlanningInterfaceTestManager() void PlanningInterfaceTestManager::publishOdometry( rclcpp::Node::SharedPtr target_node, std::string topic_name, const double shift) { - test_utils::publishToTargetNode( - test_node_, target_node, topic_name, odom_pub_, test_utils::makeOdometry(shift)); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, odom_pub_, autoware::test_utils::makeOdometry(shift)); } void PlanningInterfaceTestManager::publishMaxVelocity( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, max_velocity_pub_, VelocityLimit{}); } @@ -48,66 +48,67 @@ void PlanningInterfaceTestManager::publishPointCloud( { PointCloud2 point_cloud_msg{}; point_cloud_msg.header.frame_id = "base_link"; - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, point_cloud_pub_, point_cloud_msg); } void PlanningInterfaceTestManager::publishAcceleration( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, acceleration_pub_, AccelWithCovarianceStamped{}); } void PlanningInterfaceTestManager::publishPredictedObjects( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, predicted_objects_pub_, PredictedObjects{}); } void PlanningInterfaceTestManager::publishExpandStopRange( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, expand_stop_range_pub_, ExpandStopRange{}); } void PlanningInterfaceTestManager::publishOccupancyGrid( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( - test_node_, target_node, topic_name, occupancy_grid_pub_, test_utils::makeCostMapMsg()); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, occupancy_grid_pub_, + autoware::test_utils::makeCostMapMsg()); } void PlanningInterfaceTestManager::publishCostMap( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( - test_node_, target_node, topic_name, cost_map_pub_, test_utils::makeCostMapMsg()); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, cost_map_pub_, autoware::test_utils::makeCostMapMsg()); } void PlanningInterfaceTestManager::publishMap( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( - test_node_, target_node, topic_name, map_pub_, test_utils::makeMapBinMsg()); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, map_pub_, autoware::test_utils::makeMapBinMsg()); } void PlanningInterfaceTestManager::publishLaneDrivingScenario( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, lane_driving_scenario_pub_, - test_utils::makeScenarioMsg(Scenario::LANEDRIVING)); + autoware::test_utils::makeScenarioMsg(Scenario::LANEDRIVING)); } void PlanningInterfaceTestManager::publishParkingScenario( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, parking_scenario_pub_, - test_utils::makeScenarioMsg(Scenario::PARKING)); + autoware::test_utils::makeScenarioMsg(Scenario::PARKING)); } void PlanningInterfaceTestManager::publishInitialPose( @@ -115,69 +116,70 @@ void PlanningInterfaceTestManager::publishInitialPose( ModuleName module_name) { if (module_name == ModuleName::START_PLANNER) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, initial_pose_pub_, autoware_planning_test_manager::utils::makeInitialPoseFromLaneId(10291)); } else { - test_utils::publishToTargetNode( - test_node_, target_node, topic_name, initial_pose_pub_, test_utils::makeInitialPose(shift)); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, initial_pose_pub_, + autoware::test_utils::makeInitialPose(shift)); } } void PlanningInterfaceTestManager::publishParkingState( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, parking_state_pub_, std_msgs::msg::Bool{}); } void PlanningInterfaceTestManager::publishTrajectory( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, trajectory_pub_, Trajectory{}); } void PlanningInterfaceTestManager::publishRoute( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( - test_node_, target_node, topic_name, route_pub_, test_utils::makeNormalRoute()); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, route_pub_, autoware::test_utils::makeNormalRoute()); } void PlanningInterfaceTestManager::publishTF( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, TF_pub_, - test_utils::makeTFMsg(target_node, "base_link", "map")); + autoware::test_utils::makeTFMsg(target_node, "base_link", "map")); } void PlanningInterfaceTestManager::publishLateralOffset( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, lateral_offset_pub_, LateralOffset{}); } void PlanningInterfaceTestManager::publishOperationModeState( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, operation_mode_state_pub_, OperationModeState{}); } void PlanningInterfaceTestManager::publishTrafficSignals( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, traffic_signals_pub_, TrafficLightGroupArray{}); } void PlanningInterfaceTestManager::publishVirtualTrafficLightState( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, virtual_traffic_light_states_pub_, VirtualTrafficLightStateArray{}); } @@ -185,9 +187,9 @@ void PlanningInterfaceTestManager::publishVirtualTrafficLightState( void PlanningInterfaceTestManager::publishInitialPoseTF( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, initial_pose_tf_pub_, - test_utils::makeTFMsg(target_node, "odom", "base_link")); + autoware::test_utils::makeTFMsg(target_node, "odom", "base_link")); } void PlanningInterfaceTestManager::setTrajectoryInputTopicName(std::string topic_name) @@ -233,100 +235,101 @@ void PlanningInterfaceTestManager::setOdometryTopicName(std::string topic_name) void PlanningInterfaceTestManager::publishNominalTrajectory( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, normal_trajectory_pub_, - test_utils::generateTrajectory(10, 1.0), 5); + autoware::test_utils::generateTrajectory(10, 1.0), 5); } void PlanningInterfaceTestManager::publishAbnormalTrajectory( rclcpp::Node::SharedPtr target_node, const Trajectory & abnormal_trajectory) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, input_trajectory_name_, abnormal_trajectory_pub_, abnormal_trajectory); } void PlanningInterfaceTestManager::publishNominalRoute( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( - test_node_, target_node, topic_name, normal_route_pub_, test_utils::makeNormalRoute(), 5); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, normal_route_pub_, autoware::test_utils::makeNormalRoute(), + 5); } void PlanningInterfaceTestManager::publishBehaviorNominalRoute( rclcpp::Node::SharedPtr target_node, std::string topic_name, ModuleName module_name) { if (module_name == ModuleName::START_PLANNER) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, behavior_normal_route_pub_, autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId(10291, 10333), 5); } else { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, behavior_normal_route_pub_, - test_utils::makeBehaviorNormalRoute(), 5); + autoware::test_utils::makeBehaviorNormalRoute(), 5); } } void PlanningInterfaceTestManager::publishAbnormalRoute( rclcpp::Node::SharedPtr target_node, const LaneletRoute & abnormal_route) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, input_route_name_, abnormal_route_pub_, abnormal_route, 5); } void PlanningInterfaceTestManager::publishNominalPathWithLaneId( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, normal_path_with_lane_id_pub_, - test_utils::loadPathWithLaneIdInYaml(), 5); + autoware::test_utils::loadPathWithLaneIdInYaml(), 5); } void PlanningInterfaceTestManager::publishAbNominalPathWithLaneId( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, abnormal_path_with_lane_id_pub_, PathWithLaneId{}, 5); } void PlanningInterfaceTestManager::publishNominalPath( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, normal_path_pub_, motion_utils::convertToPath( - test_utils::loadPathWithLaneIdInYaml()), + autoware::test_utils::loadPathWithLaneIdInYaml()), 5); } void PlanningInterfaceTestManager::publishAbnormalPath( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishToTargetNode( + autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, abnormal_path_pub_, Path{}, 5); } void PlanningInterfaceTestManager::setTrajectorySubscriber(std::string topic_name) { - test_utils::setSubscriber(test_node_, topic_name, traj_sub_, count_); + autoware::test_utils::setSubscriber(test_node_, topic_name, traj_sub_, count_); } void PlanningInterfaceTestManager::setRouteSubscriber(std::string topic_name) { - test_utils::setSubscriber(test_node_, topic_name, route_sub_, count_); + autoware::test_utils::setSubscriber(test_node_, topic_name, route_sub_, count_); } void PlanningInterfaceTestManager::setScenarioSubscriber(std::string topic_name) { - test_utils::setSubscriber(test_node_, topic_name, scenario_sub_, count_); + autoware::test_utils::setSubscriber(test_node_, topic_name, scenario_sub_, count_); } void PlanningInterfaceTestManager::setPathWithLaneIdSubscriber(std::string topic_name) { - test_utils::setSubscriber(test_node_, topic_name, path_with_lane_id_sub_, count_); + autoware::test_utils::setSubscriber(test_node_, topic_name, path_with_lane_id_sub_, count_); } void PlanningInterfaceTestManager::setPathSubscriber(std::string topic_name) { - test_utils::setSubscriber(test_node_, topic_name, path_sub_, count_); + autoware::test_utils::setSubscriber(test_node_, topic_name, path_sub_, count_); } // test for normal working @@ -339,9 +342,10 @@ void PlanningInterfaceTestManager::testWithNominalTrajectory(rclcpp::Node::Share void PlanningInterfaceTestManager::testWithAbnormalTrajectory(rclcpp::Node::SharedPtr target_node) { publishAbnormalTrajectory(target_node, Trajectory{}); - publishAbnormalTrajectory(target_node, test_utils::generateTrajectory(1, 0.0)); publishAbnormalTrajectory( - target_node, test_utils::generateTrajectory(10, 0.0, 0.0, 0.0, 0.0, 1)); + target_node, autoware::test_utils::generateTrajectory(1, 0.0)); + publishAbnormalTrajectory( + target_node, autoware::test_utils::generateTrajectory(10, 0.0, 0.0, 0.0, 0.0, 1)); } // test for normal working @@ -455,4 +459,4 @@ int PlanningInterfaceTestManager::getReceivedTopicNum() return count_; } -} // namespace planning_test_utils +} // namespace autoware::planning_test_manager diff --git a/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp b/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp index 78f57e0fe104d..33ef0a1817af8 100644 --- a/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp +++ b/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp @@ -16,18 +16,18 @@ #include #include -#include +#include #include #include +using autoware::planning_test_manager::PlanningInterfaceTestManager; using autoware::planning_validator::PlanningValidator; -using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { - auto test_manager = std::make_shared(); + auto test_manager = std::make_shared(); // set subscriber with topic name: planning_validator → test_node_ test_manager->setTrajectorySubscriber("planning_validator/output/trajectory"); @@ -43,13 +43,13 @@ std::shared_ptr generateTestManager() std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto planning_validator_dir = ament_index_cpp::get_package_share_directory("autoware_planning_validator"); node_options.arguments( {"--ros-args", "--params-file", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", planning_validator_dir + "/config/planning_validator.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index 3a0aeb8d8c981..0e5ae5aa63c3e 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -14,11 +14,11 @@ autoware_internal_msgs autoware_planning_msgs autoware_route_handler + autoware_test_utils geometry_msgs lanelet2_extension motion_utils nav_msgs - planning_test_utils rclcpp rclcpp_components std_msgs diff --git a/planning/autoware_route_handler/README.md b/planning/autoware_route_handler/README.md index e8df4fd087930..bc62f06db7520 100644 --- a/planning/autoware_route_handler/README.md +++ b/planning/autoware_route_handler/README.md @@ -4,8 +4,8 @@ ## Unit Testing -The unit testing depends on `planning_test_utils` package. -`planning_test_utils` is a library that provides several common functions to simplify unit test creating. +The unit testing depends on `autoware_test_utils` package. +`autoware_test_utils` is a library that provides several common functions to simplify unit test creating. ![route_handler_test](./images/route_handler_test.svg) @@ -15,4 +15,4 @@ By default, route file is necessary to create tests. The following illustrates t ![lane_change_test_route](./images/lane_change_test_route.svg) -- The route is based on map that can be obtained from `planning_test_utils\test_map` +- The route is based on map that can be obtained from `autoware_test_utils\test_map` diff --git a/planning/autoware_route_handler/images/route_handler_test.svg b/planning/autoware_route_handler/images/route_handler_test.svg index 38b2a97da0432..445fec1dd88d0 100644 --- a/planning/autoware_route_handler/images/route_handler_test.svg +++ b/planning/autoware_route_handler/images/route_handler_test.svg @@ -212,7 +212,7 @@ >
- planning_test_utils + autoware_test_utils
diff --git a/planning/autoware_route_handler/package.xml b/planning/autoware_route_handler/package.xml index 48b1b055b2157..61a8a43b31461 100644 --- a/planning/autoware_route_handler/package.xml +++ b/planning/autoware_route_handler/package.xml @@ -24,9 +24,9 @@ autoware_map_msgs autoware_planning_msgs + autoware_test_utils geometry_msgs lanelet2_extension - planning_test_utils rclcpp rclcpp_components tf2_ros diff --git a/planning/autoware_route_handler/test/test_route_handler.hpp b/planning/autoware_route_handler/test/test_route_handler.hpp index bc557a82b196d..292cbaa6ba7d9 100644 --- a/planning/autoware_route_handler/test/test_route_handler.hpp +++ b/planning/autoware_route_handler/test/test_route_handler.hpp @@ -16,9 +16,9 @@ #define TEST_ROUTE_HANDLER_HPP_ #include "ament_index_cpp/get_package_share_directory.hpp" +#include "autoware_test_utils/autoware_test_utils.hpp" +#include "autoware_test_utils/mock_data_parser.hpp" #include "gtest/gtest.h" -#include "planning_test_utils/mock_data_parser.hpp" -#include "planning_test_utils/planning_test_utils.hpp" #include #include @@ -44,11 +44,12 @@ class TestRouteHandler : public ::testing::Test public: TestRouteHandler() { - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto lanelet2_path = planning_test_utils_dir + "/test_map/2km_test.osm"; + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); + const auto lanelet2_path = autoware_test_utils_dir + "/test_map/2km_test.osm"; constexpr double center_line_resolution = 5.0; - const auto map_bin_msg = test_utils::make_map_bin_msg(lanelet2_path, center_line_resolution); + const auto map_bin_msg = + autoware::test_utils::make_map_bin_msg(lanelet2_path, center_line_resolution); route_handler_ = std::make_shared(map_bin_msg); set_lane_change_test_route(); } @@ -61,9 +62,10 @@ class TestRouteHandler : public ::testing::Test void set_lane_change_test_route() { - const auto route_handler_dir = ament_index_cpp::get_package_share_directory("route_handler"); + const auto route_handler_dir = + ament_index_cpp::get_package_share_directory("autoware_route_handler"); const auto rh_test_route = route_handler_dir + "/test_route/lane_change_test_route.yaml"; - route_handler_->setRoute(test_utils::parse_lanelet_route_file(rh_test_route)); + route_handler_->setRoute(autoware::test_utils::parse_lanelet_route_file(rh_test_route)); } std::shared_ptr route_handler_; diff --git a/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp index 052c455c477a7..1b90992dae715 100644 --- a/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp +++ b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -24,7 +24,7 @@ #include namespace autoware::scenario_selector { -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index efa500b66f914..e6b812ff9b388 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -43,9 +43,9 @@ ament_cmake_gmock ament_lint_auto + autoware_behavior_path_planner autoware_behavior_velocity_planner autoware_lint_common - behavior_path_planner ros_testing rosidl_interface_packages diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py index 02d9cbc1e24a0..07f8f3e30e659 100644 --- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py @@ -55,7 +55,7 @@ def generate_test_description(): "config/static_centerline_generator.param.yaml", ), os.path.join( - get_package_share_directory("behavior_path_planner"), + get_package_share_directory("autoware_behavior_path_planner"), "config/behavior_path_planner.param.yaml", ), os.path.join( diff --git a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp index 30a64955366e4..d4374e21686e7 100644 --- a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp +++ b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp @@ -16,14 +16,14 @@ #include #include -#include +#include #include #include +using autoware::planning_test_manager::PlanningInterfaceTestManager; using autoware::velocity_smoother::VelocitySmootherNode; -using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -39,14 +39,14 @@ std::shared_ptr generateNode() auto node_options = rclcpp::NodeOptions{}; node_options.append_parameter_override("algorithm_type", "JerkFiltered"); node_options.append_parameter_override("publish_debug_trajs", false); - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto velocity_smoother_dir = ament_index_cpp::get_package_share_directory("autoware_velocity_smoother"); node_options.arguments( - {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", - "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + {"--ros-args", "--params-file", autoware_test_utils_dir + "/config/test_common.param.yaml", + "--params-file", autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + "--params-file", autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml", "--params-file", velocity_smoother_dir + "/config/default_common.param.yaml", "--params-file", velocity_smoother_dir + "/config/JerkFiltered.param.yaml"}); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp index 9a6205a830279..3c7b7d1df9bf5 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp @@ -23,7 +23,7 @@ #include using autoware::motion_velocity_planner::MotionVelocityPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; +using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -45,8 +45,8 @@ std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto motion_velocity_planner_dir = ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node"); const auto velocity_smoother_dir = @@ -67,10 +67,10 @@ std::shared_ptr generateNode() params.emplace_back("is_simulation", false); node_options.parameter_overrides(params); - test_utils::updateNodeOptions( - node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + autoware::test_utils::updateNodeOptions( + node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml", velocity_smoother_dir + "/config/Analytical.param.yaml", motion_velocity_planner_dir + "/config/motion_velocity_planner.param.yaml", diff --git a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp index 4e846d9ff1417..474ed9a338725 100644 --- a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp +++ b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp @@ -16,14 +16,14 @@ #include #include -#include +#include #include #include +using autoware::planning_test_manager::PlanningInterfaceTestManager; using motion_planning::ObstacleStopPlannerNode; -using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { @@ -38,17 +38,17 @@ std::shared_ptr generateNode() { auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto obstacle_stop_planner_dir = ament_index_cpp::get_package_share_directory("obstacle_stop_planner"); node_options.append_parameter_override("enable_slow_down", false); node_options.arguments( - {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", - "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + {"--ros-args", "--params-file", autoware_test_utils_dir + "/config/test_common.param.yaml", + "--params-file", autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + "--params-file", autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", obstacle_stop_planner_dir + "/config/common.param.yaml", "--params-file", obstacle_stop_planner_dir + "/config/adaptive_cruise_control.param.yaml", "--params-file", obstacle_stop_planner_dir + "/config/obstacle_stop_planner.param.yaml"});