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

Require libfranka 0.5.0

parent 041d3eb3
No related branches found
No related tags found
No related merge requests found
......@@ -2,7 +2,7 @@
## 0.6.0 - UNRELEASED
Requires `libfranka` >= 0.6.0
Requires `libfranka` >= 0.5.0
* **BREAKING** Updated joint limits in URDF
* **BREAKING** Fixed velocity, acceleration and jerk limits in `franka_hw`
......
......@@ -21,7 +21,7 @@ find_package(catkin REQUIRED COMPONENTS
tf2_msgs
)
find_package(Franka 0.4.0 REQUIRED)
find_package(Franka 0.5.0 REQUIRED)
add_service_files(FILES
SetCartesianImpedance.srv
......
......@@ -20,7 +20,7 @@ find_package(catkin REQUIRED COMPONENTS
)
find_package(Eigen3 REQUIRED)
find_package(Franka 0.3.0 REQUIRED)
find_package(Franka 0.5.0 REQUIRED)
add_message_files(FILES
JointTorqueComparison.msg
......
......@@ -14,7 +14,7 @@ find_package(catkin REQUIRED COMPONENTS
actionlib_msgs
)
find_package(Franka 0.4.0 REQUIRED)
find_package(Franka 0.5.0 REQUIRED)
add_action_files(
DIRECTORY action
......
......@@ -11,7 +11,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
)
find_package(Franka 0.4.0 REQUIRED)
find_package(Franka 0.5.0 REQUIRED)
catkin_package(
INCLUDE_DIRS include
......
......@@ -9,7 +9,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
)
find_package(Franka 0.3.0 REQUIRED)
find_package(Franka 0.5.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