Skip to content

Commit fbfc01d

Browse files
authored
Use target_compile_definitions instead of installing test files (#2009)
1 parent d4139b7 commit fbfc01d

File tree

5 files changed

+41
-51
lines changed

5 files changed

+41
-51
lines changed

controller_interface/CMakeLists.txt

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,11 +45,12 @@ if(BUILD_TESTING)
4545
)
4646

4747
ament_add_gmock(test_controller_with_options test/test_controller_with_options.cpp)
48-
install(FILES test/test_controller_node_options.yaml
49-
DESTINATION test)
5048
target_link_libraries(test_controller_with_options
5149
controller_interface
5250
)
51+
target_compile_definitions(
52+
test_controller_with_options
53+
PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR}/test/")
5354

5455
ament_add_gmock(test_chainable_controller_interface test/test_chainable_controller_interface.cpp)
5556
target_link_libraries(test_chainable_controller_interface

controller_interface/test/test_controller_with_options.cpp

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@
1616

1717
#include <gtest/gtest.h>
1818
#include <string>
19-
#include "ament_index_cpp/get_package_prefix.hpp"
2019

2120
class FriendControllerWithOptions : public controller_with_options::ControllerWithOptions
2221
{
@@ -95,8 +94,8 @@ TEST(ControllerWithOption, init_with_node_options_arguments_parameters_file)
9594
rclcpp::init(argc, argv);
9695
// creates the controller
9796
FriendControllerWithOptions controller;
98-
const std::string params_file_path = ament_index_cpp::get_package_prefix("controller_interface") +
99-
"/test/test_controller_node_options.yaml";
97+
const std::string params_file_path =
98+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_node_options.yaml");
10099
std::cerr << params_file_path << std::endl;
101100
auto controller_node_options = controller.define_custom_node_options();
102101
controller_node_options.arguments({"--ros-args", "--params-file", params_file_path});
@@ -129,8 +128,8 @@ TEST(
129128
rclcpp::init(argc, argv);
130129
// creates the controller
131130
FriendControllerWithOptions controller;
132-
const std::string params_file_path = ament_index_cpp::get_package_prefix("controller_interface") +
133-
"/test/test_controller_node_options.yaml";
131+
const std::string params_file_path =
132+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_node_options.yaml");
134133
std::cerr << params_file_path << std::endl;
135134
auto controller_node_options = controller.define_custom_node_options();
136135
controller_node_options.arguments(

controller_manager/CMakeLists.txt

Lines changed: 3 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@ endif()
1111
set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
1212

1313
set(THIS_PACKAGE_INCLUDE_DEPENDS
14-
ament_index_cpp
1514
controller_interface
1615
controller_manager_msgs
1716
diagnostic_updater
@@ -201,6 +200,9 @@ if(BUILD_TESTING)
201200
test_controller
202201
ros2_control_test_assets::ros2_control_test_assets
203202
)
203+
target_compile_definitions(
204+
test_spawner_unspawner
205+
PRIVATE PARAMETERS_FILE_PATH="${CMAKE_CURRENT_LIST_DIR}/test/")
204206

205207
ament_add_gmock(test_hardware_spawner
206208
test/test_hardware_spawner.cpp
@@ -212,14 +214,6 @@ if(BUILD_TESTING)
212214
ros2_control_test_assets::ros2_control_test_assets
213215
)
214216

215-
install(FILES
216-
test/test_controller_spawner_with_type.yaml
217-
test/test_controller_overriding_parameters.yaml
218-
test/test_controller_spawner_with_fallback_controllers.yaml
219-
test/test_controller_spawner_wildcard_entries.yaml
220-
test/test_controller_spawner_with_interfaces.yaml
221-
DESTINATION test)
222-
223217
ament_add_gmock(test_hardware_management_srvs
224218
test/test_hardware_management_srvs.cpp
225219
)

controller_manager/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,6 @@
1212
<buildtool_depend>ament_cmake_gen_version_h</buildtool_depend>
1313
<buildtool_depend>ament_cmake_python</buildtool_depend>
1414

15-
<depend>ament_index_cpp</depend>
1615
<depend>backward_ros</depend>
1716
<depend>controller_interface</depend>
1817
<depend>controller_manager_msgs</depend>

controller_manager/test/test_spawner_unspawner.cpp

Lines changed: 31 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -257,8 +257,8 @@ TEST_F(TestLoadController, multi_ctrls_test_type_in_param)
257257

258258
TEST_F(TestLoadController, spawner_test_with_params_file_string_parameter)
259259
{
260-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
261-
"/test/test_controller_spawner_with_type.yaml";
260+
const std::string test_file_path =
261+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
262262

263263
cm_->set_parameter(rclcpp::Parameter(
264264
"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)
301301

302302
TEST_F(TestLoadController, spawner_test_type_in_params_file)
303303
{
304-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
305-
"/test/test_controller_spawner_with_type.yaml";
304+
const std::string test_file_path =
305+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
306306

307307
ControllerManagerRunner cm_runner(this);
308308
// Provide controller type via the parsed file
@@ -368,8 +368,8 @@ TEST_F(TestLoadController, spawner_test_type_in_params_file)
368368

369369
TEST_F(TestLoadController, spawner_test_with_wildcard_entries_with_no_ctrl_name)
370370
{
371-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
372-
"/test/test_controller_spawner_wildcard_entries.yaml";
371+
const std::string test_file_path = std::string(PARAMETERS_FILE_PATH) +
372+
std::string("test_controller_spawner_wildcard_entries.yaml");
373373

374374
ControllerManagerRunner cm_runner(this);
375375
// Provide controller type via the parsed file
@@ -439,8 +439,8 @@ TEST_F(TestLoadController, spawner_test_with_wildcard_entries_with_no_ctrl_name)
439439

440440
TEST_F(TestLoadController, spawner_test_failed_activation_of_controllers)
441441
{
442-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
443-
"/test/test_controller_spawner_with_interfaces.yaml";
442+
const std::string test_file_path =
443+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_interfaces.yaml");
444444

445445
ControllerManagerRunner cm_runner(this);
446446
// Provide controller type via the parsed file
@@ -577,11 +577,9 @@ TEST_F(TestLoadController, unload_on_kill_activate_as_group)
577577
TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding)
578578
{
579579
const std::string main_test_file_path =
580-
ament_index_cpp::get_package_prefix("controller_manager") +
581-
"/test/test_controller_spawner_with_type.yaml";
580+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
582581
const std::string overriding_test_file_path =
583-
ament_index_cpp::get_package_prefix("controller_manager") +
584-
"/test/test_controller_overriding_parameters.yaml";
582+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_overriding_parameters.yaml");
585583

586584
ControllerManagerRunner cm_runner(this);
587585
EXPECT_EQ(
@@ -631,11 +629,9 @@ TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding)
631629
TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding_reverse)
632630
{
633631
const std::string main_test_file_path =
634-
ament_index_cpp::get_package_prefix("controller_manager") +
635-
"/test/test_controller_overriding_parameters.yaml";
632+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_overriding_parameters.yaml");
636633
const std::string overriding_test_file_path =
637-
ament_index_cpp::get_package_prefix("controller_manager") +
638-
"/test/test_controller_spawner_with_type.yaml";
634+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
639635

640636
ControllerManagerRunner cm_runner(this);
641637
EXPECT_EQ(
@@ -684,8 +680,9 @@ TEST_F(TestLoadController, spawner_test_to_check_parameter_overriding_reverse)
684680

685681
TEST_F(TestLoadController, spawner_test_fallback_controllers)
686682
{
687-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
688-
"/test/test_controller_spawner_with_fallback_controllers.yaml";
683+
const std::string test_file_path =
684+
std::string(PARAMETERS_FILE_PATH) +
685+
std::string("test_controller_spawner_with_fallback_controllers.yaml");
689686

690687
cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME));
691688
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)
10311028

10321029
TEST_F(TestLoadControllerWithNamespacedCM, spawner_test_type_in_params_file)
10331030
{
1034-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
1035-
"/test/test_controller_spawner_with_type.yaml";
1031+
const std::string test_file_path =
1032+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
10361033

10371034
ControllerManagerRunner cm_runner(this);
10381035
// Provide controller type via the parsed file
@@ -1106,8 +1103,8 @@ TEST_F(TestLoadControllerWithNamespacedCM, spawner_test_type_in_params_file)
11061103
TEST_F(
11071104
TestLoadControllerWithNamespacedCM, spawner_test_type_in_params_file_deprecated_namespace_arg)
11081105
{
1109-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
1110-
"/test/test_controller_spawner_with_type.yaml";
1106+
const std::string test_file_path =
1107+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
11111108

11121109
ControllerManagerRunner cm_runner(this);
11131110
// Provide controller type via the parsed file
@@ -1196,8 +1193,8 @@ TEST_F(
11961193

11971194
TEST_F(TestLoadControllerWithNamespacedCM, spawner_test_with_wildcard_entries_in_params_file)
11981195
{
1199-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
1200-
"/test/test_controller_spawner_with_type.yaml";
1196+
const std::string test_file_path =
1197+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
12011198

12021199
ControllerManagerRunner cm_runner(this);
12031200
// Provide controller type via the parsed file
@@ -1263,8 +1260,8 @@ TEST_F(
12631260
TestLoadControllerWithNamespacedCM,
12641261
spawner_test_fail_namespaced_controllers_with_non_wildcard_entries)
12651262
{
1266-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
1267-
"/test/test_controller_spawner_with_type.yaml";
1263+
const std::string test_file_path =
1264+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
12681265

12691266
ControllerManagerRunner cm_runner(this);
12701267
// Provide controller type via the parsed file
@@ -1303,11 +1300,11 @@ TEST_F(
13031300

13041301
TEST_F(TestLoadController, spawner_test_parsing_multiple_params_file)
13051302
{
1306-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
1307-
"/test/test_controller_spawner_with_type.yaml";
1303+
const std::string test_file_path =
1304+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
13081305
const std::string fallback_test_file_path =
1309-
ament_index_cpp::get_package_prefix("controller_manager") +
1310-
"/test/test_controller_spawner_with_fallback_controllers.yaml";
1306+
std::string(PARAMETERS_FILE_PATH) +
1307+
std::string("test_controller_spawner_with_fallback_controllers.yaml");
13111308

13121309
cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME));
13131310
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)
13701367

13711368
TEST_F(TestLoadController, spawner_test_parsing_same_params_file_multiple_times)
13721369
{
1373-
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
1374-
"/test/test_controller_spawner_with_type.yaml";
1370+
const std::string test_file_path =
1371+
std::string(PARAMETERS_FILE_PATH) + std::string("test_controller_spawner_with_type.yaml");
13751372
const std::string fallback_test_file_path =
1376-
ament_index_cpp::get_package_prefix("controller_manager") +
1377-
"/test/test_controller_spawner_with_fallback_controllers.yaml";
1373+
std::string(PARAMETERS_FILE_PATH) +
1374+
std::string("test_controller_spawner_with_fallback_controllers.yaml");
13781375

13791376
cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME));
13801377
cm_->set_parameter(rclcpp::Parameter("ctrl_2.type", test_controller::TEST_CONTROLLER_CLASS_NAME));

0 commit comments

Comments
 (0)