90 lines
3.1 KiB
YAML
90 lines
3.1 KiB
YAML
# Joints limits
|
|
#
|
|
# Sources:
|
|
#
|
|
# - Universal Robots e-Series, User Manual, UR3e, Version 5.8
|
|
# https://s3-eu-west-1.amazonaws.com/ur-support-site/69043/99403_UR3e_User_Manual_en_Global.pdf
|
|
# - Support > Articles > UR articles > Max. joint torques
|
|
# https://www.universal-robots.com/articles/ur-articles/max-joint-torques
|
|
# retrieved: 2020-06-16, last modified: 2020-06-09
|
|
joint_limits:
|
|
shoulder_pan_joint:
|
|
# acceleration limits are not publicly available
|
|
has_acceleration_limits: false
|
|
has_effort_limits: true
|
|
has_position_limits: true
|
|
has_velocity_limits: true
|
|
max_effort: 56.0
|
|
max_position: !degrees 360.0
|
|
max_velocity: !degrees 180.0
|
|
min_position: !degrees -360.0
|
|
shoulder_lift_joint:
|
|
# acceleration limits are not publicly available
|
|
has_acceleration_limits: false
|
|
has_effort_limits: true
|
|
has_position_limits: true
|
|
has_velocity_limits: true
|
|
max_effort: 56.0
|
|
max_position: !degrees 360.0
|
|
max_velocity: !degrees 180.0
|
|
min_position: !degrees -360.0
|
|
elbow_joint:
|
|
# acceleration limits are not publicly available
|
|
has_acceleration_limits: false
|
|
has_effort_limits: true
|
|
has_position_limits: true
|
|
has_velocity_limits: true
|
|
max_effort: 28.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 180.0
|
|
min_position: !degrees -180.0
|
|
wrist_1_joint:
|
|
# acceleration limits are not publicly available
|
|
has_acceleration_limits: false
|
|
has_effort_limits: true
|
|
has_position_limits: true
|
|
has_velocity_limits: true
|
|
max_effort: 12.0
|
|
max_position: !degrees 360.0
|
|
max_velocity: !degrees 360.0
|
|
min_position: !degrees -360.0
|
|
wrist_2_joint:
|
|
# acceleration limits are not publicly available
|
|
has_acceleration_limits: false
|
|
has_effort_limits: true
|
|
has_position_limits: true
|
|
has_velocity_limits: true
|
|
max_effort: 12.0
|
|
max_position: !degrees 360.0
|
|
max_velocity: !degrees 360.0
|
|
min_position: !degrees -360.0
|
|
wrist_3_joint:
|
|
# acceleration limits are not publicly available
|
|
has_acceleration_limits: false
|
|
has_effort_limits: true
|
|
has_position_limits: true
|
|
has_velocity_limits: true
|
|
max_effort: 12.0
|
|
max_position: !degrees 360.0
|
|
max_velocity: !degrees 360.0
|
|
min_position: !degrees -360.0
|
|
gripper_gap:
|
|
# acceleration limits are not publicly available
|
|
has_acceleration_limits: false
|
|
has_effort_limits: true
|
|
has_position_limits: true
|
|
has_velocity_limits: true
|
|
max_effort: 235.0
|
|
max_position: 0.14
|
|
max_velocity: 0.15
|
|
min_position: 0.0 |