Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update acceleration limits for robot configs #195

Merged
merged 3 commits into from
Jan 8, 2024
Merged
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
60 changes: 60 additions & 0 deletions panda_moveit_config/config/joint_limits_jerk_limited.yaml
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
Loading