From b03efae63bad45d30e4a75fa780c5408f7c531f3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 22 Nov 2025 00:48:48 +0100 Subject: [PATCH 1/2] Remove parameter_traits dependency (#2022) (cherry picked from commit ec198b1d98ccb9a5271fa654396e18086aaa72cd) # Conflicts: # pid_controller/CMakeLists.txt --- pid_controller/CMakeLists.txt | 16 +++++++++++++++- pid_controller/package.xml | 1 - 2 files changed, 15 insertions(+), 2 deletions(-) diff --git a/pid_controller/CMakeLists.txt b/pid_controller/CMakeLists.txt index 937f1708ce..f7b336f2e6 100644 --- a/pid_controller/CMakeLists.txt +++ b/pid_controller/CMakeLists.txt @@ -22,7 +22,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS controller_interface generate_parameter_library hardware_interface - parameter_traits pluginlib rclcpp rclcpp_lifecycle @@ -49,6 +48,7 @@ target_include_directories(pid_controller PUBLIC $ ) target_link_libraries(pid_controller PUBLIC +<<<<<<< HEAD pid_controller_parameters ) ament_target_dependencies(pid_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) @@ -56,6 +56,20 @@ ament_target_dependencies(pid_controller PUBLIC ${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(pid_controller PRIVATE "PID_CONTROLLER_BUILDING_DLL") +======= + pid_controller_parameters + angles::angles + control_toolbox::control_toolbox + controller_interface::controller_interface + hardware_interface::hardware_interface + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + realtime_tools::realtime_tools + ${std_srvs_TARGETS} + ${control_msgs_TARGETS} + ${std_srvs_TARGETS}) +>>>>>>> ec198b1 (Remove parameter_traits dependency (#2022)) pluginlib_export_plugin_description_file(controller_interface pid_controller.xml) diff --git a/pid_controller/package.xml b/pid_controller/package.xml index 40d82cb920..58aa2d5c9b 100644 --- a/pid_controller/package.xml +++ b/pid_controller/package.xml @@ -28,7 +28,6 @@ control_toolbox controller_interface hardware_interface - parameter_traits pluginlib rclcpp rclcpp_lifecycle From cfd4b2fb80553a6f3e3e22d9f473acd6e27ab72b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 22 Nov 2025 19:47:12 +0100 Subject: [PATCH 2/2] Update CMakeLists.txt --- pid_controller/CMakeLists.txt | 15 --------------- 1 file changed, 15 deletions(-) diff --git a/pid_controller/CMakeLists.txt b/pid_controller/CMakeLists.txt index f7b336f2e6..2bacddf46a 100644 --- a/pid_controller/CMakeLists.txt +++ b/pid_controller/CMakeLists.txt @@ -48,7 +48,6 @@ target_include_directories(pid_controller PUBLIC $ ) target_link_libraries(pid_controller PUBLIC -<<<<<<< HEAD pid_controller_parameters ) ament_target_dependencies(pid_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) @@ -56,20 +55,6 @@ ament_target_dependencies(pid_controller PUBLIC ${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(pid_controller PRIVATE "PID_CONTROLLER_BUILDING_DLL") -======= - pid_controller_parameters - angles::angles - control_toolbox::control_toolbox - controller_interface::controller_interface - hardware_interface::hardware_interface - pluginlib::pluginlib - rclcpp::rclcpp - rclcpp_lifecycle::rclcpp_lifecycle - realtime_tools::realtime_tools - ${std_srvs_TARGETS} - ${control_msgs_TARGETS} - ${std_srvs_TARGETS}) ->>>>>>> ec198b1 (Remove parameter_traits dependency (#2022)) pluginlib_export_plugin_description_file(controller_interface pid_controller.xml)