diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index dd0c6b835f..4f28622bd6 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -10,30 +10,30 @@ find_package(hardware_interface REQUIRED) find_package(rclcpp_lifecycle REQUIRED) add_library( - controller_interface + ${PROJECT_NAME} SHARED src/controller_interface_base.cpp src/controller_interface.cpp src/chainable_controller_interface.cpp ) target_include_directories( - controller_interface + ${PROJECT_NAME} PRIVATE include ) ament_target_dependencies( - controller_interface + ${PROJECT_NAME} hardware_interface rclcpp_lifecycle ) # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. -target_compile_definitions(controller_interface PRIVATE "CONTROLLER_INTERFACE_BUILDING_DLL") +target_compile_definitions(${PROJECT_NAME} PRIVATE "CONTROLLER_INTERFACE_BUILDING_DLL") install(DIRECTORY include/ DESTINATION include ) -install(TARGETS controller_interface +install(TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin @@ -46,15 +46,15 @@ if(BUILD_TESTING) find_package(sensor_msgs REQUIRED) ament_add_gmock(test_controller_interface test/test_controller_interface.cpp) - target_link_libraries(test_controller_interface controller_interface) + target_link_libraries(test_controller_interface ${PROJECT_NAME}) target_include_directories(test_controller_interface PRIVATE include) ament_add_gmock(test_controller_with_options test/test_controller_with_options.cpp) - target_link_libraries(test_controller_with_options controller_interface) + target_link_libraries(test_controller_with_options ${PROJECT_NAME}) target_include_directories(test_controller_with_options PRIVATE include) ament_add_gmock(test_chainable_controller_interface test/test_chainable_controller_interface.cpp) - target_link_libraries(test_chainable_controller_interface controller_interface) + target_link_libraries(test_chainable_controller_interface ${PROJECT_NAME}) target_include_directories(test_chainable_controller_interface PRIVATE include) ament_target_dependencies(test_chainable_controller_interface hardware_interface) @@ -99,6 +99,6 @@ ament_export_include_directories( include ) ament_export_libraries( - controller_interface + ${PROJECT_NAME} ) ament_package() diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index 5224043772..b103e4c094 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -5,42 +5,37 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra) endif() +set(THIS_PACKAGE_INCLUDE_DEPENDS + ament_index_cpp + controller_interface + controller_manager_msgs + hardware_interface + pluginlib + rclcpp +) + find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) find_package(ament_cmake_core REQUIRED) -find_package(ament_index_cpp REQUIRED) -find_package(controller_interface REQUIRED) -find_package(controller_manager_msgs REQUIRED) -find_package(hardware_interface REQUIRED) -find_package(pluginlib REQUIRED) -find_package(rclcpp REQUIRED) - -add_library(controller_manager SHARED +foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() + +add_library(${PROJECT_NAME} SHARED src/controller_manager.cpp ) -target_include_directories(controller_manager PRIVATE include) -ament_target_dependencies(controller_manager - ament_index_cpp - controller_interface - controller_manager_msgs - hardware_interface - pluginlib - rclcpp -) +target_include_directories(${PROJECT_NAME} PRIVATE include) +ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS}) # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. -target_compile_definitions(controller_manager PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") +target_compile_definitions(${PROJECT_NAME} PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") add_executable(ros2_control_node src/ros2_control_node.cpp) target_include_directories(ros2_control_node PRIVATE include) -target_link_libraries(ros2_control_node controller_manager) -ament_target_dependencies(ros2_control_node - controller_interface - hardware_interface - rclcpp -) +target_link_libraries(ros2_control_node ${PROJECT_NAME}) +ament_target_dependencies(ros2_control_node ${THIS_PACKAGE_INCLUDE_DEPENDS}) -install(TARGETS controller_manager +install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin LIBRARY DESTINATION lib ARCHIVE DESTINATION lib @@ -76,7 +71,7 @@ if(BUILD_TESTING) add_library(test_controller SHARED test/test_controller/test_controller.cpp) target_include_directories(test_controller PRIVATE include) - target_link_libraries(test_controller controller_manager) + target_link_libraries(test_controller ${PROJECT_NAME}) target_compile_definitions(test_controller PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") pluginlib_export_plugin_description_file( controller_interface test/test_controller/test_controller.xml) @@ -86,7 +81,7 @@ if(BUILD_TESTING) add_library(test_controller_failed_init SHARED test/test_controller_failed_init/test_controller_failed_init.cpp) target_include_directories(test_controller_failed_init PRIVATE include) - target_link_libraries(test_controller_failed_init controller_manager) + target_link_libraries(test_controller_failed_init ${PROJECT_NAME}) target_compile_definitions(test_controller_failed_init PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") pluginlib_export_plugin_description_file( controller_interface test/test_controller_failed_init/test_controller_failed_init.xml) @@ -99,7 +94,7 @@ if(BUILD_TESTING) test/test_controller_manager.cpp ) target_include_directories(test_controller_manager PRIVATE include) - target_link_libraries(test_controller_manager controller_manager test_controller) + target_link_libraries(test_controller_manager ${PROJECT_NAME} test_controller) ament_target_dependencies(test_controller_manager ros2_control_test_assets) ament_add_gmock( @@ -107,7 +102,7 @@ if(BUILD_TESTING) test/test_controller_manager_with_namespace.cpp ) target_include_directories(test_controller_manager_with_namespace.cpp PRIVATE include) - target_link_libraries(test_controller_manager_with_namespace.cpp controller_manager test_controller) + target_link_libraries(test_controller_manager_with_namespace.cpp ${PROJECT_NAME} test_controller) ament_target_dependencies(test_controller_manager_with_namespace.cpp ros2_control_test_assets) ament_add_gmock( @@ -116,7 +111,7 @@ if(BUILD_TESTING) APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$ ) target_include_directories(test_load_controller PRIVATE include) - target_link_libraries(test_load_controller controller_manager test_controller test_controller_failed_init) + target_link_libraries(test_load_controller ${PROJECT_NAME} test_controller test_controller_failed_init) ament_target_dependencies(test_load_controller ros2_control_test_assets) ament_add_gmock( @@ -125,7 +120,7 @@ if(BUILD_TESTING) APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$ ) target_include_directories(test_controller_manager_srvs PRIVATE include) - target_link_libraries(test_controller_manager_srvs controller_manager test_controller) + target_link_libraries(test_controller_manager_srvs ${PROJECT_NAME} test_controller) ament_target_dependencies( test_controller_manager_srvs controller_manager_msgs @@ -134,7 +129,7 @@ if(BUILD_TESTING) add_library(test_controller_with_interfaces SHARED test/test_controller_with_interfaces/test_controller_with_interfaces.cpp) target_include_directories(test_controller_with_interfaces PRIVATE include) - target_link_libraries(test_controller_with_interfaces controller_manager) + target_link_libraries(test_controller_with_interfaces ${PROJECT_NAME}) target_compile_definitions(test_controller_with_interfaces PRIVATE "CONTROLLER_MANAGER_BUILDING_DLL") pluginlib_export_plugin_description_file( controller_interface test/test_controller_with_interfaces/test_controller_with_interfaces.xml) @@ -148,7 +143,7 @@ if(BUILD_TESTING) APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$ ) target_include_directories(test_release_interfaces PRIVATE include) - target_link_libraries(test_release_interfaces controller_manager test_controller_with_interfaces) + target_link_libraries(test_release_interfaces ${PROJECT_NAME} test_controller_with_interfaces) ament_target_dependencies(test_release_interfaces ros2_control_test_assets) ament_add_gmock( @@ -156,7 +151,7 @@ if(BUILD_TESTING) test/test_spawner_unspawner.cpp ) target_include_directories(test_spawner_unspawner PRIVATE include) - target_link_libraries(test_spawner_unspawner controller_manager test_controller) + target_link_libraries(test_spawner_unspawner ${PROJECT_NAME} test_controller) ament_target_dependencies(test_spawner_unspawner ros2_control_test_assets) ament_add_gmock( @@ -164,7 +159,7 @@ if(BUILD_TESTING) test/test_hardware_management_srvs.cpp ) target_include_directories(test_hardware_management_srvs PRIVATE include) - target_link_libraries(test_hardware_management_srvs controller_manager test_controller) + target_link_libraries(test_hardware_management_srvs ${PROJECT_NAME} test_controller) ament_target_dependencies( test_hardware_management_srvs controller_manager_msgs @@ -176,16 +171,12 @@ endif() ament_python_install_package(${PROJECT_NAME} SCRIPTS_DESTINATION lib/${PROJECT_NAME}) ament_export_libraries( - controller_manager + ${PROJECT_NAME} ) ament_export_include_directories( include ) ament_export_dependencies( - controller_interface - controller_manager_msgs - hardware_interface - pluginlib - rclcpp + ${THIS_PACKAGE_INCLUDE_DEPENDS} ) ament_package() diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index 73b4ecf379..69f1a4d5da 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -5,18 +5,24 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra) endif() +set(THIS_PACKAGE_INCLUDE_DEPENDS + control_msgs + lifecycle_msgs + pluginlib + rclcpp_lifecycle + rcpputils + rcutils + tinyxml2_vendor + TinyXML2 +) + find_package(ament_cmake REQUIRED) -find_package(control_msgs REQUIRED) -find_package(lifecycle_msgs REQUIRED) -find_package(pluginlib REQUIRED) -find_package(rclcpp_lifecycle REQUIRED) -find_package(rcpputils REQUIRED) -find_package(rcutils REQUIRED) -find_package(tinyxml2_vendor REQUIRED) -find_package(TinyXML2 REQUIRED) +foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() add_library( - hardware_interface + ${PROJECT_NAME} SHARED src/actuator.cpp src/component_parser.cpp @@ -25,22 +31,14 @@ add_library( src/system.cpp ) target_include_directories( - hardware_interface + ${PROJECT_NAME} PUBLIC include ) -ament_target_dependencies( - hardware_interface - control_msgs - lifecycle_msgs - pluginlib - rclcpp_lifecycle - rcutils - rcpputils -) +ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS}) # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. -target_compile_definitions(hardware_interface PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL") +target_compile_definitions(${PROJECT_NAME} PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL") # Fake components add_library( @@ -55,7 +53,7 @@ target_include_directories( ) target_link_libraries( fake_components - hardware_interface + ${PROJECT_NAME} ) ament_target_dependencies( fake_components @@ -67,7 +65,7 @@ ament_target_dependencies( target_compile_definitions(fake_components PRIVATE "HARDWARE_INTERFACE_BUILDING_DLL") pluginlib_export_plugin_description_file( - hardware_interface fake_components_plugin_description.xml) + ${PROJECT_NAME} fake_components_plugin_description.xml) install( DIRECTORY include/ @@ -77,7 +75,7 @@ install( install( TARGETS fake_components - hardware_interface + ${PROJECT_NAME} RUNTIME DESTINATION bin ARCHIVE DESTINATION lib LIBRARY DESTINATION lib @@ -99,28 +97,28 @@ if(BUILD_TESTING) ament_target_dependencies(test_macros rcpputils) ament_add_gmock(test_joint_handle test/test_handle.cpp) - target_link_libraries(test_joint_handle hardware_interface) + target_link_libraries(test_joint_handle ${PROJECT_NAME}) ament_target_dependencies(test_joint_handle rcpputils) ament_add_gmock(test_component_interfaces test/test_component_interfaces.cpp) - target_link_libraries(test_component_interfaces hardware_interface) + target_link_libraries(test_component_interfaces ${PROJECT_NAME}) ament_add_gmock(test_component_parser test/test_component_parser.cpp) - target_link_libraries(test_component_parser hardware_interface) + target_link_libraries(test_component_parser ${PROJECT_NAME}) ament_target_dependencies(test_component_parser ros2_control_test_assets) add_library(test_components SHARED test/test_components/test_actuator.cpp test/test_components/test_sensor.cpp test/test_components/test_system.cpp) - target_link_libraries(test_components hardware_interface) + target_link_libraries(test_components ${PROJECT_NAME}) ament_target_dependencies(test_components pluginlib) install(TARGETS test_components DESTINATION lib ) pluginlib_export_plugin_description_file( - hardware_interface test/test_components/test_components.xml) + ${PROJECT_NAME} test/test_components/test_components.xml) add_library(test_hardware_components SHARED test/test_hardware_components/test_single_joint_actuator.cpp @@ -128,23 +126,23 @@ if(BUILD_TESTING) test/test_hardware_components/test_two_joint_system.cpp test/test_hardware_components/test_system_with_command_modes.cpp ) - target_link_libraries(test_hardware_components hardware_interface) + target_link_libraries(test_hardware_components ${PROJECT_NAME}) ament_target_dependencies(test_hardware_components pluginlib) install(TARGETS test_hardware_components DESTINATION lib ) pluginlib_export_plugin_description_file( - hardware_interface test/test_hardware_components/test_hardware_components.xml + ${PROJECT_NAME} test/test_hardware_components/test_hardware_components.xml ) ament_add_gmock(test_resource_manager test/test_resource_manager.cpp) - target_link_libraries(test_resource_manager hardware_interface) + target_link_libraries(test_resource_manager ${PROJECT_NAME}) ament_target_dependencies(test_resource_manager ros2_control_test_assets) ament_add_gmock(test_generic_system test/fake_components/test_generic_system.cpp) target_include_directories(test_generic_system PRIVATE include) - target_link_libraries(test_generic_system hardware_interface) + target_link_libraries(test_generic_system ${PROJECT_NAME}) ament_target_dependencies(test_generic_system pluginlib ros2_control_test_assets @@ -156,15 +154,7 @@ ament_export_include_directories( ) ament_export_libraries( fake_components - hardware_interface -) -ament_export_dependencies( - control_msgs - lifecycle_msgs - rclcpp_lifecycle - pluginlib - rcpputils - tinyxml2_vendor - TinyXML2 + ${PROJECT_NAME} ) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) ament_package() diff --git a/ros2_control_test_assets/CMakeLists.txt b/ros2_control_test_assets/CMakeLists.txt index f210e134f1..970b3abd01 100644 --- a/ros2_control_test_assets/CMakeLists.txt +++ b/ros2_control_test_assets/CMakeLists.txt @@ -1,7 +1,6 @@ cmake_minimum_required(VERSION 3.5) project(ros2_control_test_assets) -# find dependencies find_package(ament_cmake REQUIRED) install( diff --git a/transmission_interface/CMakeLists.txt b/transmission_interface/CMakeLists.txt index 72e3faf4aa..72130c28c9 100644 --- a/transmission_interface/CMakeLists.txt +++ b/transmission_interface/CMakeLists.txt @@ -5,35 +5,33 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -# find dependencies +set(THIS_PACKAGE_INCLUDE_DEPENDS + hardware_interface + pluginlib + rclcpp +) + find_package(ament_cmake REQUIRED) -find_package(hardware_interface REQUIRED) -find_package(pluginlib REQUIRED) -find_package(rclcpp REQUIRED) +foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() install( DIRECTORY include/ DESTINATION include ) -add_library(transmission_interface SHARED +add_library(${PROJECT_NAME} SHARED src/simple_transmission_loader.cpp src/four_bar_linkage_transmission_loader.cpp src/differential_transmission_loader.cpp ) +target_include_directories(${PROJECT_NAME} PUBLIC include) +ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS}) -target_include_directories(transmission_interface PUBLIC include) - -ament_target_dependencies( - transmission_interface - pluginlib - hardware_interface - rclcpp -) - -pluginlib_export_plugin_description_file(transmission_interface ros2_control_plugins.xml) +pluginlib_export_plugin_description_file(${PROJECT_NAME} ros2_control_plugins.xml) -install(TARGETS transmission_interface +install(TARGETS ${PROJECT_NAME} EXPORT export_${PROJECT_NAME} RUNTIME DESTINATION bin ARCHIVE DESTINATION lib @@ -100,7 +98,7 @@ ament_export_dependencies( ) ament_export_libraries( - transmission_interface + ${PROJECT_NAME} ) ament_package()