-
Notifications
You must be signed in to change notification settings - Fork 118
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Update acceleration limits for robot configs (#195)
* update panda Signed-off-by: Paul Gesel <[email protected]> * rename file to joint_limits_jerk_limited.yaml Signed-off-by: Paul Gesel <[email protected]> * rename to hard_joint_limits.yaml Signed-off-by: Paul Gesel <[email protected]> --------- Signed-off-by: Paul Gesel <[email protected]> Signed-off-by: Paul Gesel <[email protected]>
- Loading branch information
Showing
1 changed file
with
60 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,60 @@ | ||
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed | ||
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] | ||
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits, has_jerk_limits] | ||
# Joint limits set from this config: https://frankaemika.github.io/docs/control_parameters.html | ||
|
||
joint_limits: | ||
panda_joint1: | ||
has_velocity_limits: true | ||
max_velocity: 2.1750 | ||
has_acceleration_limits: true | ||
max_acceleration: 15.0 | ||
has_jerk_limits: false | ||
panda_joint2: | ||
has_velocity_limits: true | ||
max_velocity: 2.1750 | ||
has_acceleration_limits: true | ||
max_acceleration: 7.5 | ||
has_jerk_limits: false | ||
panda_joint3: | ||
has_velocity_limits: true | ||
max_velocity: 2.1750 | ||
has_acceleration_limits: true | ||
max_acceleration: 10.0 | ||
has_jerk_limits: false | ||
panda_joint4: | ||
has_velocity_limits: true | ||
max_velocity: 2.1750 | ||
has_acceleration_limits: true | ||
max_acceleration: 12.5 | ||
has_jerk_limits: false | ||
panda_joint5: | ||
has_velocity_limits: true | ||
max_velocity: 2.6100 | ||
has_acceleration_limits: true | ||
max_acceleration: 15.0 | ||
has_jerk_limits: false | ||
panda_joint6: | ||
has_velocity_limits: true | ||
max_velocity: 2.6100 | ||
has_acceleration_limits: true | ||
max_acceleration: 20.0 | ||
has_jerk_limits: false | ||
panda_joint7: | ||
has_velocity_limits: true | ||
max_velocity: 2.6100 | ||
has_acceleration_limits: true | ||
max_acceleration: 20.0 | ||
has_jerk_limits: false | ||
panda_finger_joint1: | ||
has_velocity_limits: true | ||
max_velocity: 0.1 | ||
has_acceleration_limits: true | ||
max_acceleration: 1.0 | ||
has_jerk_limits: false | ||
panda_finger_joint2: | ||
has_velocity_limits: true | ||
max_velocity: 0.1 | ||
has_acceleration_limits: true | ||
max_acceleration: 1.0 | ||
has_jerk_limits: false |