Skip to content
Snippets Groups Projects
Commit c4413251 authored by Florian Walch's avatar Florian Walch
Browse files

Fix franka_example_controllers dependencies

parent 5b3bcd49
No related branches found
No related tags found
No related merge requests found
# CHANGELOG
## 0.2.1 - UNRELEASED
Requires `libfranka` >= 0.2.0
* Added missing dependency to `franka_example_controllers`
## 0.2.0 - 2018-01-29
Requires `libfranka` >= 0.2.0
......
......@@ -21,7 +21,7 @@ find_package(catkin REQUIRED COMPONENTS
tf2_msgs
)
find_package(Franka REQUIRED)
find_package(Franka 0.2.0 REQUIRED)
add_service_files(FILES
SetCartesianImpedance.srv
......
......@@ -17,6 +17,7 @@ find_package(catkin REQUIRED COMPONENTS
)
find_package(Eigen3 REQUIRED)
find_package(Franka 0.2.0 REQUIRED)
add_message_files(FILES
JointTorqueComparison.msg
......@@ -33,6 +34,7 @@ catkin_package(
INCLUDE_DIRS include
LIBRARIES franka_example_controllers
CATKIN_DEPENDS controller_interface franka_hw pluginlib
DEPENDS Franka
)
include_directories(include ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS})
......@@ -56,7 +58,10 @@ add_dependencies(franka_example_controllers
${PROJECT_NAME}_gencfg
)
target_link_libraries(franka_example_controllers ${catkin_LIBRARIES})
target_link_libraries(franka_example_controllers
${catkin_LIBRARIES}
Franka::Franka
)
## Installation
install(TARGETS franka_example_controllers
......
......@@ -20,6 +20,7 @@
<depend>controller_interface</depend>
<depend>franka_hw</depend>
<depend>libfranka</depend>
<depend>pluginlib</depend>
<depend>realtime_tools</depend>
......
......@@ -14,7 +14,7 @@ find_package(catkin REQUIRED COMPONENTS
actionlib_msgs
)
find_package(Franka REQUIRED)
find_package(Franka 0.2.0 REQUIRED)
add_action_files(
DIRECTORY action
......
......@@ -11,7 +11,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
)
find_package(Franka REQUIRED)
find_package(Franka 0.2.0 REQUIRED)
catkin_package(
INCLUDE_DIRS include
......
......@@ -9,7 +9,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
)
find_package(Franka REQUIRED)
find_package(Franka 0.2.0 REQUIRED)
catkin_package(CATKIN_DEPENDS sensor_msgs roscpp)
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment