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

Add missing build_export_depends, don't install example controller includes

parent 64557fc3
No related branches found
No related tags found
No related merge requests found
......@@ -5,6 +5,7 @@
Requires `libfranka` >= 0.2.0
* Catkin-related fixes for `franka_example_controllers`
* Added missing `<build_export_depend>` for `message_runtime`
## 0.2.1 - 2018-01-30
......
......@@ -35,6 +35,8 @@
<exec_depend>message_runtime</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<build_export_depend>message_runtime</build_export_depend>
<export>
<controller_interface plugin="${prefix}/franka_controller_plugins.xml"/>
</export>
......
......@@ -33,9 +33,16 @@ generate_dynamic_reconfigure_options(
)
catkin_package(
INCLUDE_DIRS include
LIBRARIES franka_example_controllers
CATKIN_DEPENDS controller_interface franka_hw pluginlib geometry_msgs message_runtime
CATKIN_DEPENDS
controller_interface
dynamic_reconfigure
franka_hw
geometry_msgs
message_runtime
pluginlib
realtime_tools
roscpp
DEPENDS Franka
)
......@@ -71,9 +78,6 @@ install(TARGETS franka_example_controllers
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)
install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
......
......@@ -13,17 +13,19 @@
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>eigen</build_depend>
<build_export_depend>message_runtime</build_export_depend>
<depend>controller_interface</depend>
<depend>dynamic_reconfigure</depend>
<depend>franka_hw</depend>
<depend>geometry_msgs</depend>
<depend>libfranka</depend>
<depend>pluginlib</depend>
<depend>realtime_tools</depend>
<depend>roscpp</depend>
<exec_depend>franka_description</exec_depend>
<exec_depend>message_runtime</exec_depend>
......
......@@ -23,4 +23,6 @@
<depend>actionlib_msgs</depend>
<exec_depend>message_runtime</exec_depend>
<build_export_depend>message_runtime</build_export_depend>
</package>
......@@ -16,6 +16,7 @@
<depend>std_msgs</depend>
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
<build_export_depend>message_runtime</build_export_depend>
<export>
<architecture_independent/>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment