Skip to content
Snippets Groups Projects
Commit d5f07a99 authored by Christoph Jähne's avatar Christoph Jähne
Browse files

franka 0.5 -> franka 0.7, fixed cmake for service lib

parent c6a7a4d4
No related branches found
No related tags found
No related merge requests found
...@@ -19,11 +19,11 @@ find_package(catkin REQUIRED COMPONENTS ...@@ -19,11 +19,11 @@ find_package(catkin REQUIRED COMPONENTS
tf2_msgs tf2_msgs
) )
find_package(Franka 0.5.0 REQUIRED) find_package(Franka 0.7.0 REQUIRED)
catkin_package( catkin_package(
INCLUDE_DIRS include INCLUDE_DIRS include
LIBRARIES franka_state_controller franka_control_services LIBRARIES franka_state_controller
CATKIN_DEPENDS CATKIN_DEPENDS
controller_interface controller_interface
franka_hw franka_hw
......
...@@ -22,7 +22,7 @@ find_package(catkin REQUIRED COMPONENTS ...@@ -22,7 +22,7 @@ find_package(catkin REQUIRED COMPONENTS
) )
find_package(Eigen3 REQUIRED) find_package(Eigen3 REQUIRED)
find_package(Franka 0.5.0 REQUIRED) find_package(Franka 0.7.0 REQUIRED)
add_message_files(FILES add_message_files(FILES
JointTorqueComparison.msg JointTorqueComparison.msg
......
...@@ -14,7 +14,7 @@ find_package(catkin REQUIRED COMPONENTS ...@@ -14,7 +14,7 @@ find_package(catkin REQUIRED COMPONENTS
actionlib_msgs actionlib_msgs
) )
find_package(Franka 0.5.0 REQUIRED) find_package(Franka 0.7.0 REQUIRED)
add_action_files( add_action_files(
DIRECTORY action DIRECTORY action
......
...@@ -17,11 +17,11 @@ find_package(catkin REQUIRED COMPONENTS ...@@ -17,11 +17,11 @@ find_package(catkin REQUIRED COMPONENTS
message_generation message_generation
) )
find_package(Franka 0.5.0 REQUIRED) find_package(Franka 0.7.0 REQUIRED)
catkin_package( catkin_package(
INCLUDE_DIRS include INCLUDE_DIRS include
LIBRARIES franka_hw LIBRARIES franka_hw franka_control_services
CATKIN_DEPENDS CATKIN_DEPENDS
actionlib_msgs actionlib_msgs
actionlib actionlib
......
...@@ -9,7 +9,7 @@ find_package(catkin REQUIRED COMPONENTS ...@@ -9,7 +9,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp roscpp
) )
find_package(Franka 0.5.0 REQUIRED) find_package(Franka 0.7.0 REQUIRED)
catkin_package(CATKIN_DEPENDS sensor_msgs roscpp) 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