Skip to content

Commit

Permalink
CMakeLists cleanup (#733)
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe authored Jun 16, 2022
1 parent ebef6e7 commit 6434833
Show file tree
Hide file tree
Showing 5 changed files with 88 additions and 110 deletions.
18 changes: 9 additions & 9 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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)

Expand Down Expand Up @@ -99,6 +99,6 @@ ament_export_include_directories(
include
)
ament_export_libraries(
controller_interface
${PROJECT_NAME}
)
ament_package()
73 changes: 32 additions & 41 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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)
Expand All @@ -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)
Expand All @@ -99,15 +94,15 @@ 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(
test_controller_manager_with_namespace.cpp
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(
Expand All @@ -116,7 +111,7 @@ if(BUILD_TESTING)
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$<CONFIG>
)
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(
Expand All @@ -125,7 +120,7 @@ if(BUILD_TESTING)
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$<CONFIG>
)
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
Expand All @@ -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)
Expand All @@ -148,23 +143,23 @@ if(BUILD_TESTING)
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$<CONFIG>
)
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(
test_spawner_unspawner
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(
test_hardware_management_srvs
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
Expand All @@ -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()
Loading

0 comments on commit 6434833

Please sign in to comment.