Skip to content

Commit db0846e

Browse files
Modernize CMakeLists (#688) (#697)
(cherry picked from commit 2e53b95) Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent 8d13afc commit db0846e

File tree

2 files changed

+29
-11
lines changed

2 files changed

+29
-11
lines changed

gz_ros2_control/CMakeLists.txt

Lines changed: 29 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ find_package(controller_manager REQUIRED)
1717
find_package(hardware_interface REQUIRED)
1818
find_package(pluginlib REQUIRED)
1919
find_package(rclcpp REQUIRED)
20+
find_package(rclcpp_lifecycle REQUIRED)
2021
find_package(yaml_cpp_vendor REQUIRED)
2122

2223
find_package(gz_sim_vendor REQUIRED)
@@ -30,18 +31,23 @@ include_directories(include)
3031
add_library(${PROJECT_NAME}-system SHARED
3132
src/gz_ros2_control_plugin.cpp
3233
)
34+
add_library(${PROJECT_NAME}-system::${PROJECT_NAME}-system ALIAS ${PROJECT_NAME}-system)
3335

3436
target_link_libraries(${PROJECT_NAME}-system
3537
PUBLIC
3638
gz-sim::gz-sim
3739
gz-plugin::register
3840
ament_index_cpp::ament_index_cpp
3941
controller_manager::controller_manager
40-
hardware_interface::mock_components
41-
pluginlib::pluginlib
42+
hardware_interface::hardware_interface
43+
${pluginlib_TARGETS}
4244
rclcpp::rclcpp
4345
rclcpp_lifecycle::rclcpp_lifecycle
4446
)
47+
target_include_directories(${PROJECT_NAME}-system PUBLIC
48+
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
49+
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
50+
)
4551

4652
#########
4753

@@ -51,22 +57,29 @@ add_library(gz_hardware_plugins SHARED
5157
target_link_libraries(gz_hardware_plugins
5258
PUBLIC
5359
gz-sim::gz-sim
54-
hardware_interface::mock_components
60+
hardware_interface::hardware_interface
5561
rclcpp::rclcpp
5662
rclcpp_lifecycle::rclcpp_lifecycle
5763
)
5864

59-
## Install
65+
# Install headers
66+
install(DIRECTORY include/
67+
DESTINATION include/${PROJECT_NAME}
68+
)
69+
70+
# Install library and export targets
6071
install(TARGETS
72+
${PROJECT_NAME}-system
6173
gz_hardware_plugins
74+
EXPORT export_${PROJECT_NAME}
6275
ARCHIVE DESTINATION lib
6376
LIBRARY DESTINATION lib
6477
RUNTIME DESTINATION bin
6578
)
6679

67-
install(DIRECTORY
68-
include/
69-
DESTINATION include
80+
install(EXPORT export_${PROJECT_NAME}
81+
NAMESPACE ${PROJECT_NAME}::
82+
DESTINATION share/${PROJECT_NAME}/cmake
7083
)
7184

7285
# Testing and linting
@@ -75,12 +88,18 @@ if(BUILD_TESTING)
7588
ament_lint_auto_find_test_dependencies()
7689
endif()
7790

91+
# Export old-style CMake variables
7892
ament_export_include_directories(include)
7993
ament_export_libraries(${PROJECT_NAME}-system gz_hardware_plugins)
8094

81-
# Install directories
82-
install(TARGETS ${PROJECT_NAME}-system
83-
DESTINATION lib
95+
# Export modern CMake targets
96+
ament_export_targets(
97+
export_${PROJECT_NAME}
98+
)
99+
100+
ament_export_dependencies(
101+
controller_manager
102+
hardware_interface
84103
)
85104

86105
pluginlib_export_plugin_description_file(gz_ros2_control gz_hardware_plugins.xml)

gz_ros2_control/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@
1111
<buildtool_depend>ament_cmake</buildtool_depend>
1212

1313
<depend>ament_index_cpp</depend>
14-
<!-- default version to use in official ROS 2 packages is Gazebo Harmonic for ROS 2 Rolling -->
1514
<depend>gz_sim_vendor</depend>
1615
<depend>gz_plugin_vendor</depend>
1716
<depend>pluginlib</depend>

0 commit comments

Comments
 (0)