From fbfc01d84de1ed4f02b39ba2d77ab492c0afea0b Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 23 Jan 2025 12:42:09 +0100 Subject: [PATCH] Use `target_compile_definitions` instead of installing test files (#2009) --- controller_interface/CMakeLists.txt | 5 +- .../test/test_controller_with_options.cpp | 9 ++- controller_manager/CMakeLists.txt | 12 +--- controller_manager/package.xml | 1 - .../test/test_spawner_unspawner.cpp | 65 +++++++++---------- 5 files changed, 41 insertions(+), 51 deletions(-) diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index dc810eaeb5..10604a5255 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -45,11 +45,12 @@ if(BUILD_TESTING) ) ament_add_gmock(test_controller_with_options test/test_controller_with_options.cpp) - install(FILES test/test_controller_node_options.yaml - DESTINATION test) target_link_libraries(test_controller_with_options controller_interface ) + target_compile_definitions( + test_controller_with_options + PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR}/test/") ament_add_gmock(test_chainable_controller_interface test/test_chainable_controller_interface.cpp) target_link_libraries(test_chainable_controller_interface diff --git a/controller_interface/test/test_controller_with_options.cpp b/controller_interface/test/test_controller_with_options.cpp index eb60c19aca..80b6c5cf3b 100644 --- a/controller_interface/test/test_controller_with_options.cpp +++ b/controller_interface/test/test_controller_with_options.cpp @@ -16,7 +16,6 @@ #include #include -#include "ament_index_cpp/get_package_prefix.hpp" class FriendControllerWithOptions : public controller_with_options::ControllerWithOptions { @@ -95,8 +94,8 @@ TEST(ControllerWithOption, init_with_node_options_arguments_parameters_file) rclcpp::init(argc, argv); // creates the controller FriendControllerWithOptions controller; - const std::string params_file_path = ament_index_cpp::get_package_prefix("controller_interface") + - "/test/test_controller_node_options.yaml"; + const std::string params_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_node_options.yaml"); std::cerr << params_file_path << std::endl; auto controller_node_options = controller.define_custom_node_options(); controller_node_options.arguments({"--ros-args", "--params-file", params_file_path}); @@ -129,8 +128,8 @@ TEST( rclcpp::init(argc, argv); // creates the controller FriendControllerWithOptions controller; - const std::string params_file_path = ament_index_cpp::get_package_prefix("controller_interface") + - "/test/test_controller_node_options.yaml"; + const std::string params_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_node_options.yaml"); std::cerr << params_file_path << std::endl; auto controller_node_options = controller.define_custom_node_options(); controller_node_options.arguments( diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index 5d91604cec..e704393022 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -11,7 +11,6 @@ endif() set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) set(THIS_PACKAGE_INCLUDE_DEPENDS - ament_index_cpp controller_interface controller_manager_msgs diagnostic_updater @@ -201,6 +200,9 @@ if(BUILD_TESTING) test_controller ros2_control_test_assets::ros2_control_test_assets ) + target_compile_definitions( + test_spawner_unspawner + PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR}/test/") ament_add_gmock(test_hardware_spawner test/test_hardware_spawner.cpp @@ -212,14 +214,6 @@ if(BUILD_TESTING) ros2_control_test_assets::ros2_control_test_assets ) - install(FILES - test/test_controller_spawner_with_type.yaml - test/test_controller_overriding_parameters.yaml - test/test_controller_spawner_with_fallback_controllers.yaml - test/test_controller_spawner_wildcard_entries.yaml - test/test_controller_spawner_with_interfaces.yaml - DESTINATION test) - ament_add_gmock(test_hardware_management_srvs test/test_hardware_management_srvs.cpp ) diff --git a/controller_manager/package.xml b/controller_manager/package.xml index 8e1a9b261e..61f9bceb55 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -12,7 +12,6 @@ ament_cmake_gen_version_h ament_cmake_python - ament_index_cpp backward_ros controller_interface controller_manager_msgs diff --git a/controller_manager/test/test_spawner_unspawner.cpp b/controller_manager/test/test_spawner_unspawner.cpp index ff39b69e8c..3afcdfefb9 100644 --- a/controller_manager/test/test_spawner_unspawner.cpp +++ b/controller_manager/test/test_spawner_unspawner.cpp @@ -257,8 +257,8 @@ TEST_F(TestLoadController, multi_ctrls_test_type_in_param) TEST_F(TestLoadController, spawner_test_with_params_file_string_parameter) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); cm_->set_parameter(rclcpp::Parameter( "ctrl_with_parameters_and_type.type", test_controller::TEST_CONTROLLER_CLASS_NAME)); @@ -301,8 +301,8 @@ TEST_F(TestLoadController, spawner_test_with_params_file_string_parameter) TEST_F(TestLoadController, spawner_test_type_in_params_file) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); ControllerManagerRunner cm_runner(this); // Provide controller type via the parsed file @@ -368,8 +368,8 @@ TEST_F(TestLoadController, spawner_test_type_in_params_file) TEST_F(TestLoadController, spawner_test_with_wildcard_entries_with_no_ctrl_name) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_wildcard_entries.yaml"; + const std::string test_file_path = std::string(PARAMETERS_FILE_PATH) + + std::string("test_controller_spawner_wildcard_entries.yaml"); ControllerManagerRunner cm_runner(this); // Provide controller type via the parsed file @@ -439,8 +439,8 @@ TEST_F(TestLoadController, spawner_test_with_wildcard_entries_with_no_ctrl_name) TEST_F(TestLoadController, spawner_test_failed_activation_of_controllers) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_interfaces.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_interfaces.yaml"); ControllerManagerRunner cm_runner(this); // Provide controller type via the parsed file @@ -577,11 +577,9 @@ TEST_F(TestLoadController, unload_on_kill_activate_as_group) TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding) { const std::string main_test_file_path = - ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); const std::string overriding_test_file_path = - ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_overriding_parameters.yaml"; + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_overriding_parameters.yaml"); ControllerManagerRunner cm_runner(this); EXPECT_EQ( @@ -631,11 +629,9 @@ TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding) TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding_reverse) { const std::string main_test_file_path = - ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_overriding_parameters.yaml"; + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_overriding_parameters.yaml"); const std::string overriding_test_file_path = - ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); ControllerManagerRunner cm_runner(this); EXPECT_EQ( @@ -684,8 +680,9 @@ TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding_reverse) TEST_F(TestLoadController, spawner_test_fallback_controllers) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_fallback_controllers.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + + std::string("test_controller_spawner_with_fallback_controllers.yaml"); cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME)); cm_->set_parameter(rclcpp::Parameter("ctrl_2.type", test_controller::TEST_CONTROLLER_CLASS_NAME)); @@ -1031,8 +1028,8 @@ TEST_F(TestLoadControllerWithNamespacedCM, multi_ctrls_test_type_in_param) TEST_F(TestLoadControllerWithNamespacedCM, spawner_test_type_in_params_file) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); ControllerManagerRunner cm_runner(this); // Provide controller type via the parsed file @@ -1106,8 +1103,8 @@ TEST_F(TestLoadControllerWithNamespacedCM, spawner_test_type_in_params_file) TEST_F( TestLoadControllerWithNamespacedCM, spawner_test_type_in_params_file_deprecated_namespace_arg) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); ControllerManagerRunner cm_runner(this); // Provide controller type via the parsed file @@ -1196,8 +1193,8 @@ TEST_F( TEST_F(TestLoadControllerWithNamespacedCM, spawner_test_with_wildcard_entries_in_params_file) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); ControllerManagerRunner cm_runner(this); // Provide controller type via the parsed file @@ -1263,8 +1260,8 @@ TEST_F( TestLoadControllerWithNamespacedCM, spawner_test_fail_namespaced_controllers_with_non_wildcard_entries) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); ControllerManagerRunner cm_runner(this); // Provide controller type via the parsed file @@ -1303,11 +1300,11 @@ TEST_F( TEST_F(TestLoadController, spawner_test_parsing_multiple_params_file) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); const std::string fallback_test_file_path = - ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_fallback_controllers.yaml"; + std::string(PARAMETERS_FILE_PATH) + + std::string("test_controller_spawner_with_fallback_controllers.yaml"); cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME)); cm_->set_parameter(rclcpp::Parameter("ctrl_2.type", test_controller::TEST_CONTROLLER_CLASS_NAME)); @@ -1370,11 +1367,11 @@ TEST_F(TestLoadController, spawner_test_parsing_multiple_params_file) TEST_F(TestLoadController, spawner_test_parsing_same_params_file_multiple_times) { - const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_type.yaml"; + const std::string test_file_path = + std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml"); const std::string fallback_test_file_path = - ament_index_cpp::get_package_prefix("controller_manager") + - "/test/test_controller_spawner_with_fallback_controllers.yaml"; + std::string(PARAMETERS_FILE_PATH) + + std::string("test_controller_spawner_with_fallback_controllers.yaml"); cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME)); cm_->set_parameter(rclcpp::Parameter("ctrl_2.type", test_controller::TEST_CONTROLLER_CLASS_NAME));