|
| 1 | +# Joints limits |
| 2 | +# |
| 3 | +# Sources: |
| 4 | +# |
| 5 | +# - Universal Robots e-Series, User Manual, UR16e, Version 5.8 |
| 6 | +# https://s3-eu-west-1.amazonaws.com/ur-support-site/69187/99473_UR16e_User_Manual_en_Global.pdf |
| 7 | +# - Support > Articles > UR articles > Max. joint torques |
| 8 | +# https://www.universal-robots.com/articles/ur-articles/max-joint-torques |
| 9 | +# retrieved: 2020-06-16, last modified: 2020-06-09 |
| 10 | +joint_limits: |
| 11 | + shoulder_pan_joint: |
| 12 | + # acceleration limits are not publicly available |
| 13 | + has_acceleration_limits: false |
| 14 | + has_effort_limits: true |
| 15 | + has_position_limits: true |
| 16 | + has_velocity_limits: true |
| 17 | + max_effort: 330.0 |
| 18 | + max_position: !degrees 360.0 |
| 19 | + max_velocity: !degrees 130.0 |
| 20 | + min_position: !degrees -360.0 |
| 21 | + shoulder_lift_joint: |
| 22 | + # acceleration limits are not publicly available |
| 23 | + has_acceleration_limits: false |
| 24 | + has_effort_limits: true |
| 25 | + has_position_limits: true |
| 26 | + has_velocity_limits: true |
| 27 | + max_effort: 330.0 |
| 28 | + max_position: !degrees 360.0 |
| 29 | + max_velocity: !degrees 130.0 |
| 30 | + min_position: !degrees -360.0 |
| 31 | + elbow_joint: |
| 32 | + # acceleration limits are not publicly available |
| 33 | + has_acceleration_limits: false |
| 34 | + has_effort_limits: true |
| 35 | + has_position_limits: true |
| 36 | + has_velocity_limits: true |
| 37 | + max_effort: 150.0 |
| 38 | + # we artificially limit this joint to half its actual joint position limit |
| 39 | + # to avoid (MoveIt/OMPL) planning problems, as due to the physical |
| 40 | + # construction of the robot, it's impossible to rotate the 'elbow_joint' |
| 41 | + # over more than approx +- 1 pi (the shoulder lift joint gets in the way). |
| 42 | + # |
| 43 | + # This leads to planning problems as the search space will be divided into |
| 44 | + # two sections, with no connections from one to the other. |
| 45 | + # |
| 46 | + # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for |
| 47 | + # more information. |
| 48 | + max_position: !degrees 180.0 |
| 49 | + max_velocity: !degrees 160.0 |
| 50 | + min_position: !degrees -180.0 |
| 51 | + wrist_1_joint: |
| 52 | + # acceleration limits are not publicly available |
| 53 | + has_acceleration_limits: false |
| 54 | + has_effort_limits: true |
| 55 | + has_position_limits: true |
| 56 | + has_velocity_limits: true |
| 57 | + max_effort: 56.0 |
| 58 | + max_position: !degrees 360.0 |
| 59 | + max_velocity: !degrees 220.0 |
| 60 | + min_position: !degrees -360.0 |
| 61 | + wrist_2_joint: |
| 62 | + # acceleration limits are not publicly available |
| 63 | + has_acceleration_limits: false |
| 64 | + has_effort_limits: true |
| 65 | + has_position_limits: true |
| 66 | + has_velocity_limits: true |
| 67 | + max_effort: 56.0 |
| 68 | + max_position: !degrees 360.0 |
| 69 | + max_velocity: !degrees 220.0 |
| 70 | + min_position: !degrees -360.0 |
| 71 | + wrist_3_joint: |
| 72 | + # acceleration limits are not publicly available |
| 73 | + has_acceleration_limits: false |
| 74 | + has_effort_limits: true |
| 75 | + has_position_limits: true |
| 76 | + has_velocity_limits: true |
| 77 | + max_effort: 56.0 |
| 78 | + max_position: !degrees 360.0 |
| 79 | + max_velocity: !degrees 220.0 |
| 80 | + min_position: !degrees -360.0 |
0 commit comments