Skip to content

Commit a026508

Browse files
authored
Adding export of sr_hand_finder (and sr_arm_finder) libraries such th… (shadow-robot#234)
* Adding export of sr_hand_finder (and sr_arm_finder) libraries such that they can be resolved externally.
1 parent a3fdb07 commit a026508

File tree

1 file changed

+9
-1
lines changed

1 file changed

+9
-1
lines changed

sr_utilities/CMakeLists.txt

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ catkin_package(
1919
DEPENDS
2020
CATKIN_DEPENDS sensor_msgs sr_robot_msgs rospy roscpp tf urdf std_msgs message_runtime sr_utilities_common
2121
INCLUDE_DIRS include
22-
LIBRARIES sr_calibration sr_trajectory_command_publisher
22+
LIBRARIES sr_arm_finder sr_calibration sr_hand_finder sr_trajectory_command_publisher
2323
)
2424

2525
include_directories(
@@ -62,10 +62,18 @@ install(DIRECTORY include/${PROJECT_NAME}/
6262
FILES_MATCHING PATTERN "*.hpp"
6363
)
6464

65+
install(TARGETS sr_arm_finder
66+
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
67+
)
68+
6569
install(TARGETS sr_calibration
6670
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
6771
)
6872

73+
install(TARGETS sr_hand_finder
74+
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
75+
)
76+
6977
install(TARGETS sr_trajectory_command_publisher
7078
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
7179
)

0 commit comments

Comments
 (0)