-
Notifications
You must be signed in to change notification settings - Fork 9
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
used ur_description's joint_limit file
- Loading branch information
Felix Durchdewald
authored and
Felix Durchdewald
committed
Nov 8, 2023
1 parent
2e8658e
commit 13103b5
Showing
1 changed file
with
65 additions
and
28 deletions.
There are no files selected for viewing
93 changes: 65 additions & 28 deletions
93
my_robot_cell/my_robot_cell_moveit_config/config/joint_limits.yaml
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 |
---|---|---|
@@ -1,40 +1,77 @@ | ||
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed | ||
|
||
# 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. | ||
default_velocity_scaling_factor: 0.1 | ||
default_acceleration_scaling_factor: 0.1 | ||
|
||
# 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] | ||
# Joints limits | ||
# | ||
# Sources: | ||
# | ||
# - Universal Robots e-Series, User Manual, UR20, Version 5.14 | ||
# https://s3-eu-west-1.amazonaws.com/ur-support-site/203281/706-276-00_UR20_User_Manual_en_Global.pdf | ||
joint_limits: | ||
ur20_elbow_joint: | ||
has_velocity_limits: true | ||
max_velocity: 2.6179938779914944 | ||
ur20_shoulder_pan_joint: | ||
# acceleration limits are not publicly available | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
ur20_shoulder_lift_joint: | ||
has_effort_limits: true | ||
has_position_limits: true | ||
has_velocity_limits: true | ||
max_velocity: 2.0943951023931953 | ||
max_effort: 730.0 | ||
max_position: !degrees 360.0 | ||
max_velocity: !degrees 120.0 | ||
min_position: !degrees -360.0 | ||
ur20_shoulder_lift_joint: | ||
# acceleration limits are not publicly available | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
ur20_shoulder_pan_joint: | ||
has_effort_limits: true | ||
has_position_limits: true | ||
has_velocity_limits: true | ||
max_velocity: 2.0943951023931953 | ||
max_effort: 730.0 | ||
max_position: !degrees 360.0 | ||
max_velocity: !degrees 120.0 | ||
min_position: !degrees -360.0 | ||
ur20_elbow_joint: | ||
# acceleration limits are not publicly available | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
ur20_wrist_1_joint: | ||
has_effort_limits: true | ||
has_position_limits: true | ||
has_velocity_limits: true | ||
max_velocity: 3.6651914291880923 | ||
max_effort: 430.0 | ||
# we artificially limit this joint to half its actual joint position limit | ||
# to avoid (MoveIt/OMPL) planning problems, as due to the physical | ||
# construction of the robot, it's impossible to rotate the 'elbow_joint' | ||
# over more than approx +- 1 pi (the shoulder lift joint gets in the way). | ||
# | ||
# This leads to planning problems as the search space will be divided into | ||
# two sections, with no connections from one to the other. | ||
# | ||
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for | ||
# more information. | ||
max_position: !degrees 180.0 | ||
max_velocity: !degrees 150.0 | ||
min_position: !degrees -180.0 | ||
ur20_wrist_1_joint: | ||
# acceleration limits are not publicly available | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
ur20_wrist_2_joint: | ||
has_effort_limits: true | ||
has_position_limits: true | ||
has_velocity_limits: true | ||
max_velocity: 3.6651914291880923 | ||
max_effort: 100.0 | ||
max_position: !degrees 360.0 | ||
max_velocity: !degrees 210.0 | ||
min_position: !degrees -360.0 | ||
ur20_wrist_2_joint: | ||
# acceleration limits are not publicly available | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
ur20_wrist_3_joint: | ||
has_effort_limits: true | ||
has_position_limits: true | ||
has_velocity_limits: true | ||
max_velocity: 3.6651914291880923 | ||
max_effort: 100.0 | ||
max_position: !degrees 360.0 | ||
max_velocity: !degrees 210.0 | ||
min_position: !degrees -360.0 | ||
ur20_wrist_3_joint: | ||
# acceleration limits are not publicly available | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
has_effort_limits: true | ||
has_position_limits: true | ||
has_velocity_limits: true | ||
max_effort: 100.0 | ||
max_position: !degrees 360.0 | ||
max_velocity: !degrees 210.0 | ||
min_position: !degrees -360.0 |