Skip to content

Commit

Permalink
joint limits readme
Browse files Browse the repository at this point in the history
  • Loading branch information
Aron Svastits committed Nov 20, 2023
1 parent 5166b21 commit 6fa9d97
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 46 deletions.
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,9 @@ Github CI

### Joint limit configurations

- joint limits files
The support packages contain a joint limits file for every supported robot model, necessary time parametrization of moveit-planned paths. They contain the velocity limits also available in the URDF model and additional acceleration limits. Acceleration limits can never be global, these values are calculated from the worst-case ramp-up time to reach maximum velocity. The easiest way to modify the allowed velocities and accelerations is to change the velocity and acceleration scaling factors also available in the same configuration files. (The scaling factor can never be smaller than 1.)


### Extending the models

In real applications, it's likely that your description will be more complex, involving multiple objects next to the robot. It is recommended to create a dedicated ROS2 package specifically for managing this extended description.
Expand Down
21 changes: 6 additions & 15 deletions kuka_lbr_iisy_support/config/lbr_iisy11_r1300_joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,6 @@
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration, max_jerk]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]

# The default config of moveit does not take into account the jerk limits, the RuckigTrajectorySmoothing adapter must be
# added to the planning pipeline to support jerk limits

# Easiest way to slow down the robot is to decrease the velocity and acceleration scaling factors
default_velocity_scaling_factor: 1.0
default_acceleration_scaling_factor: 1.0
Expand All @@ -14,40 +11,34 @@ joint_limits:
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 11.089258
has_jerk: true
max_jerk: 3757.777778
has_jerk: false
joint_a2:
has_velocity_limits: true
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 1.105824
has_jerk: true
max_jerk: 3391.182265
has_jerk: false
joint_a3:
has_velocity_limits: true
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 1.836823
has_jerk: true
max_jerk: 1362.865183
has_jerk: false
joint_a4:
has_velocity_limits: true
max_velocity: 4.014255
has_acceleration_limits: true
max_acceleration: 40.248068
has_jerk: true
max_jerk: 606.319878
has_jerk: false
joint_a5:
has_velocity_limits: true
max_velocity: 4.537856
has_acceleration_limits: true
max_acceleration: 43.739157
has_jerk: true
max_jerk: 598.681915
has_jerk: false
joint_a6:
has_velocity_limits: true
max_velocity: 7.504909
has_acceleration_limits: true
max_acceleration: 134.647432
has_jerk: true
max_jerk: 145.557710
has_jerk: false
21 changes: 6 additions & 15 deletions kuka_lbr_iisy_support/config/lbr_iisy15_r930_joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,6 @@
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration, max_jerk]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]

# The default config of moveit does not take into account the jerk limits, the RuckigTrajectorySmoothing adapter must be
# added to the planning pipeline to support jerk limits

# Easiest way to slow down the robot is to decrease the velocity and acceleration scaling factors
default_velocity_scaling_factor: 1.0
default_acceleration_scaling_factor: 1.0
Expand All @@ -14,40 +11,34 @@ joint_limits:
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 17.929068
has_jerk: true
max_jerk: 3685.289606
has_jerk: false
joint_a2:
has_velocity_limits: true
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 1.324527
has_jerk: true
max_jerk: 2653.054380
has_jerk: false
joint_a3:
has_velocity_limits: true
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 1.931703
has_jerk: true
max_jerk: 1274.691677
has_jerk: false
joint_a4:
has_velocity_limits: true
max_velocity: 4.014255
has_acceleration_limits: true
max_acceleration: 20.760275
has_jerk: true
max_jerk: 588.650348
has_jerk: false
joint_a5:
has_velocity_limits: true
max_velocity: 4.537856
has_acceleration_limits: true
max_acceleration: 17.729259
has_jerk: true
max_jerk: 542.410163
has_jerk: false
joint_a6:
has_velocity_limits: true
max_velocity: 7.504909
has_acceleration_limits: true
max_acceleration: 98.845225
has_jerk: true
max_jerk: 147.477480
has_jerk: false
21 changes: 6 additions & 15 deletions kuka_lbr_iisy_support/config/lbr_iisy3_r760_joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,6 @@
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration, max_jerk]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]

# The default config of moveit does not take into account the jerk limits, the RuckigTrajectorySmoothing adapter must be
# added to the planning pipeline to support jerk limits # TODO: check if jerk dimensions are ok!!

# Easiest way to slow down the robot is to decrease the velocity and acceleration scaling factors
default_velocity_scaling_factor: 1.0
default_acceleration_scaling_factor: 1.0
Expand All @@ -14,40 +11,34 @@ joint_limits:
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 17.567841
has_jerk: true
max_jerk: 892.0286289
has_jerk: false
joint_a2:
has_velocity_limits: true
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 2.101232
has_jerk: true
max_jerk: 886.576821
has_jerk: false
joint_a3:
has_velocity_limits: true
max_velocity: 3.490656
has_acceleration_limits: true
max_acceleration: 10.738869
has_jerk: true
max_jerk: 516.588450
has_jerk: false
joint_a4:
has_velocity_limits: true
max_velocity: 5.235983
has_acceleration_limits: true
max_acceleration: 27.276282
has_jerk: true
max_jerk: 175.806183
has_jerk: false
joint_a5:
has_velocity_limits: true
max_velocity: 5.235983
has_acceleration_limits: true
max_acceleration: 21.786787
has_jerk: true
max_jerk: 156.995898
has_jerk: false
joint_a6:
has_velocity_limits: true
max_velocity: 5.235983
has_acceleration_limits: true
max_acceleration: 112.291689
has_jerk: true
max_jerk: 57.552859
has_jerk: false

0 comments on commit 6fa9d97

Please sign in to comment.