Skip to content

Commit

Permalink
Update information about Ruckig and jerk limits (#168)
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe committed Apr 18, 2023
1 parent d0b92e1 commit 471e35e
Show file tree
Hide file tree
Showing 6 changed files with 42 additions and 13 deletions.
25 changes: 19 additions & 6 deletions dual_arm_panda_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -1,100 +1,113 @@
# 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]

# As MoveIt! does not support jerk limits, the acceleration limits provided here are the highest values that guarantee
# that no jerk limits will be violated. More precisely, applying Euler differentiation in the worst case (from min accel
# to max accel in 1 ms) the acceleration limits are the ones that satisfy
# max_jerk = (max_acceleration - min_acceleration) / 0.001
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits, has_jerk_limits]

joint_limits:
right_panda_joint1:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.75
has_jerk_limits: false
right_panda_joint2:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 1.875
has_jerk_limits: false
right_panda_joint3:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 2.5
has_jerk_limits: false
right_panda_joint4:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.125
has_jerk_limits: false
right_panda_joint5:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 3.75
has_jerk_limits: false
right_panda_joint6:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.0
has_jerk_limits: false
right_panda_joint7:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.0
has_jerk_limits: false
right_panda_finger_joint1:
has_velocity_limits: true
max_velocity: 0.1
has_acceleration_limits: false
max_acceleration: 0.0
has_jerk_limits: false
right_panda_finger_joint2:
has_velocity_limits: true
max_velocity: 0.1
has_acceleration_limits: false
max_acceleration: 0.0
has_jerk_limits: false
left_panda_joint1:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.75
has_jerk_limits: false
left_panda_joint2:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 1.875
has_jerk_limits: false
left_panda_joint3:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 2.5
has_jerk_limits: false
left_panda_joint4:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.125
has_jerk_limits: false
left_panda_joint5:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 3.75
has_jerk_limits: false
left_panda_joint6:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.0
has_jerk_limits: false
left_panda_joint7:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.0
has_jerk_limits: false
left_panda_finger_joint1:
has_velocity_limits: true
max_velocity: 0.1
has_acceleration_limits: false
max_acceleration: 0.0
has_jerk_limits: false
left_panda_finger_joint2:
has_velocity_limits: true
max_velocity: 0.1
has_acceleration_limits: false
max_acceleration: 0.0
has_jerk_limits: false
2 changes: 2 additions & 0 deletions dual_arm_panda_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
planning_plugin: ompl_interface/OMPLPlanner
request_adapters: >-
# Optionally use Ruckig for jerk-limited smoothing
# default_planner_request_adapters/AddRuckigTrajectorySmoothing
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
Expand Down
8 changes: 7 additions & 1 deletion fanuc_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# 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]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits, has_jerk_limits]

# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
Expand All @@ -13,28 +13,34 @@ joint_limits:
max_velocity: 3.67
has_acceleration_limits: true
max_acceleration: 0.734
has_jerk_limits: false
joint_2:
has_velocity_limits: true
max_velocity: 3.32
has_acceleration_limits: true
max_acceleration: 0.664
has_jerk_limits: false
joint_3:
has_velocity_limits: true
max_velocity: 3.67
has_acceleration_limits: true
max_acceleration: 0.734
has_jerk_limits: false
joint_4:
has_velocity_limits: true
max_velocity: 6.98
has_acceleration_limits: true
max_acceleration: 1.396
has_jerk_limits: false
joint_5:
has_velocity_limits: true
max_velocity: 6.98
has_acceleration_limits: true
max_acceleration: 1.396
has_jerk_limits: false
joint_6:
has_velocity_limits: true
max_velocity: 10.47
has_acceleration_limits: true
max_acceleration: 2.094
has_jerk_limits: false
2 changes: 2 additions & 0 deletions fanuc_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
planning_plugin: ompl_interface/OMPLPlanner
request_adapters: >-
# Optionally use Ruckig for jerk-limited smoothing
# default_planner_request_adapters/AddRuckigTrajectorySmoothing
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
Expand Down
16 changes: 10 additions & 6 deletions panda_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -1,55 +1,59 @@
# 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]

# As MoveIt! does not support jerk limits, the acceleration limits provided here are the highest values that guarantee
# that no jerk limits will be violated. More precisely, applying Euler differentiation in the worst case (from min accel
# to max accel in 1 ms) the acceleration limits are the ones that satisfy
# max_jerk = (max_acceleration - min_acceleration) / 0.001
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits, has_jerk_limits]

joint_limits:
panda_joint1:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.75
has_jerk_limits: false
panda_joint2:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 1.875
has_jerk_limits: false
panda_joint3:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 2.5
has_jerk_limits: false
panda_joint4:
has_velocity_limits: true
max_velocity: 2.1750
has_acceleration_limits: true
max_acceleration: 3.125
has_jerk_limits: false
panda_joint5:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 3.75
has_jerk_limits: false
panda_joint6:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.0
has_jerk_limits: false
panda_joint7:
has_velocity_limits: true
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5.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
2 changes: 2 additions & 0 deletions panda_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
planning_plugin: ompl_interface/OMPLPlanner
request_adapters: >-
# Optionally use Ruckig for jerk-limited smoothing
# default_planner_request_adapters/AddRuckigTrajectorySmoothing
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
Expand Down

0 comments on commit 471e35e

Please sign in to comment.