Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 8 additions & 8 deletions ur_calibration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(ur_robot_driver REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(tf2_ros REQUIRED)

find_package(Eigen3 REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
Expand All @@ -31,14 +33,13 @@ add_library(calibration
target_include_directories(calibration
PUBLIC
include
${EIGEN3_INCLUDE_DIRS}
)
target_link_libraries(calibration
ur_client_library::urcl
Eigen3::Eigen
yaml-cpp
)
ament_target_dependencies(calibration
rclcpp
ur_robot_driver
rclcpp::rclcpp
ur_robot_driver::ur_robot_driver_log_handler
)

add_executable(calibration_correction
Expand All @@ -49,9 +50,8 @@ target_include_directories(calibration_correction
include
)
target_link_libraries(calibration_correction
ur_client_library::urcl
)
target_link_libraries(calibration_correction
${sensor_msgs_TARGETS}
tf2_ros::tf2_ros
calibration
)

Expand Down
1 change: 0 additions & 1 deletion ur_calibration/src/calibration_correction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@

#include "ur_robot_driver/urcl_log_handler.hpp"

#include "ament_index_cpp/get_package_share_directory.hpp"
#include "rclcpp/exceptions/exceptions.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "tf2_ros/transform_listener.h"
Expand Down
34 changes: 22 additions & 12 deletions ur_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -113,10 +113,24 @@ target_link_libraries(${PROJECT_NAME}
freedrive_mode_controller_parameters
passthrough_trajectory_controller_parameters
ur_configuration_controller_parameters
)

ament_target_dependencies(${PROJECT_NAME}
${THIS_PACKAGE_INCLUDE_DEPENDS}
${geometry_msgs_TARGETS}
${lifecycle_msgs_TARGETS}
${std_msgs_TARGETS}
${std_srvs_TARGETS}
${tf2_geometry_msgs_TARGETS}
${ur_dashboard_msgs_TARGETS}
${control_msgs_TARGETS}
${trajectory_msgs_TARGETS}
${ur_msgs_TARGETS}
${action_msgs_TARGETS}
angles::angles
controller_interface::controller_interface
joint_trajectory_controller::joint_trajectory_controller
pluginlib::pluginlib
rclcpp_lifecycle::rclcpp_lifecycle
rcutils::rcutils
realtime_tools::realtime_tools
tf2_ros::tf2_ros
)

target_compile_options(${PROJECT_NAME} PRIVATE -Wpedantic -Werror)
Expand Down Expand Up @@ -163,20 +177,16 @@ if(BUILD_TESTING)
)
target_link_libraries(test_load_force_mode_controller
${PROJECT_NAME}
)
ament_target_dependencies(test_load_force_mode_controller
controller_manager
ros2_control_test_assets
controller_manager::controller_manager
ros2_control_test_assets::ros2_control_test_assets
)
ament_add_gmock(test_load_freedrive_mode_controller
test/test_load_freedrive_mode_controller.cpp
)
target_link_libraries(test_load_freedrive_mode_controller
${PROJECT_NAME}
)
ament_target_dependencies(test_load_freedrive_mode_controller
controller_manager
ros2_control_test_assets
controller_manager::controller_manager
ros2_control_test_assets::ros2_control_test_assets
)
endif()

Expand Down
112 changes: 78 additions & 34 deletions ur_robot_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ find_package(geometry_msgs REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclpy REQUIRED)
find_package(std_msgs REQUIRED)
Expand All @@ -37,45 +38,47 @@ find_package(ur_msgs REQUIRED)

include_directories(include)

set(THIS_PACKAGE_INCLUDE_DEPENDS
controller_manager
controller_manager_msgs
geometry_msgs
hardware_interface
pluginlib
rclcpp
rclcpp_lifecycle
std_msgs
std_srvs
tf2_geometry_msgs
ur_client_library
ur_dashboard_msgs
ur_msgs
)

add_library(ur_robot_driver_plugin
SHARED
src/dashboard_client_ros.cpp
src/hardware_interface.cpp
src/urcl_log_handler.cpp
src/robot_state_helper.cpp
)
target_link_libraries(
ur_robot_driver_plugin
target_link_libraries(ur_robot_driver_plugin PUBLIC
${controller_manager_msgs_TARGETS}
${geometry_msgs_TARGETS}
${std_msgs_TARGETS}
${std_srvs_TARGETS}
${tf2_geometry_msgs_TARGETS}
${ur_dashboard_msgs_TARGETS}
${ur_msgs_TARGETS}
controller_manager::controller_manager
hardware_interface::hardware_interface
pluginlib::pluginlib
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
ur_client_library::urcl
)
target_include_directories(
ur_robot_driver_plugin
PRIVATE
include
)
ament_target_dependencies(
ur_robot_driver_plugin
${${PROJECT_NAME}_EXPORTED_TARGETS}
${THIS_PACKAGE_INCLUDE_DEPENDS}
)
pluginlib_export_plugin_description_file(hardware_interface hardware_interface_plugin.xml)

add_library(ur_robot_driver_log_handler
SHARED
src/urcl_log_handler.cpp
)
target_include_directories(ur_robot_driver_log_handler
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(ur_robot_driver_log_handler PUBLIC
rclcpp::rclcpp
ur_client_library::urcl
)

#
# dashboard_client
#
Expand All @@ -84,8 +87,12 @@ add_executable(dashboard_client
src/dashboard_client_node.cpp
src/urcl_log_handler.cpp
)
target_link_libraries(dashboard_client ur_client_library::urcl)
ament_target_dependencies(dashboard_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})
target_link_libraries(dashboard_client PRIVATE
${std_srvs_TARGETS}
${ur_dashboard_msgs_TARGETS}
rclcpp::rclcpp
ur_client_library::urcl
)

#
# controller_stopper_node
Expand All @@ -94,7 +101,12 @@ add_executable(controller_stopper_node
src/controller_stopper.cpp
src/controller_stopper_node.cpp
)
ament_target_dependencies(controller_stopper_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})
target_link_libraries(controller_stopper_node PRIVATE
${std_msgs_TARGETS}
${controller_manager_msgs_TARGETS}
rclcpp::rclcpp
ur_client_library::urcl
)

#
# robot_state_helper
Expand All @@ -104,36 +116,56 @@ add_executable(robot_state_helper
src/robot_state_helper_node.cpp
src/urcl_log_handler.cpp
)
target_link_libraries(robot_state_helper ur_client_library::urcl)
ament_target_dependencies(robot_state_helper ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})
target_link_libraries(robot_state_helper PUBLIC
${std_msgs_TARGETS}
${std_srvs_TARGETS}
${ur_dashboard_msgs_TARGETS}
rclcpp::rclcpp
rclcpp_action::rclcpp_action
ur_client_library::urcl
)

add_executable(urscript_interface
src/urscript_interface.cpp
)
ament_target_dependencies(urscript_interface ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})
target_link_libraries(urscript_interface
rclcpp::rclcpp
${std_msgs_TARGETS}
ur_client_library::urcl
)

install(
TARGETS dashboard_client controller_stopper_node urscript_interface robot_state_helper
TARGETS
dashboard_client
controller_stopper_node
urscript_interface
robot_state_helper
DESTINATION lib/${PROJECT_NAME}
)

# INSTALL
install(
TARGETS ur_robot_driver_plugin
TARGETS
ur_robot_driver_log_handler
ur_robot_driver_plugin
EXPORT export_${PROJECT_NAME}
DESTINATION lib
)
install(
DIRECTORY include/
DESTINATION include
DESTINATION include/${PROJECT_NAME}
)

## EXPORTS
ament_export_include_directories(
include
)
ament_export_libraries(
ur_robot_driver_log_handler
ur_robot_driver_plugin
)
# Export modern CMake targets
ament_export_targets(export_${PROJECT_NAME})

install(DIRECTORY resources
DESTINATION share/${PROJECT_NAME}
Expand All @@ -150,7 +182,19 @@ ament_export_dependencies(
pluginlib
rclcpp
rclcpp_lifecycle
${THIS_PACKAGE_INCLUDE_DEPENDS}
controller_manager
controller_manager_msgs
geometry_msgs
hardware_interface
pluginlib
rclcpp
rclcpp_lifecycle
std_msgs
std_srvs
tf2_geometry_msgs
ur_client_library
ur_dashboard_msgs
ur_msgs
)

# Install Python execs
Expand Down
Loading