From 50269d12523f6d11e4c36313f0ffb5caaf24e2d1 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Thu, 13 Aug 2020 13:37:11 +0200 Subject: [PATCH] description: spec limits in degrees. Use rosparam's and xacro's support for these special constructors to convert to radians on-the-fly. --- ur_description/config/ur10/joint_limits.yaml | 36 +++++++++---------- ur_description/config/ur10e/joint_limits.yaml | 36 +++++++++---------- ur_description/config/ur16e/joint_limits.yaml | 36 +++++++++---------- ur_description/config/ur3/joint_limits.yaml | 36 +++++++++---------- ur_description/config/ur3e/joint_limits.yaml | 36 +++++++++---------- ur_description/config/ur5/joint_limits.yaml | 36 +++++++++---------- ur_description/config/ur5e/joint_limits.yaml | 36 +++++++++---------- 7 files changed, 126 insertions(+), 126 deletions(-) diff --git a/ur_description/config/ur10/joint_limits.yaml b/ur_description/config/ur10/joint_limits.yaml index 9778c2601..9e55c53cb 100644 --- a/ur_description/config/ur10/joint_limits.yaml +++ b/ur_description/config/ur10/joint_limits.yaml @@ -15,9 +15,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 330.0 - max_position: 6.28318530718 - max_velocity: 2.0943951 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 shoulder_lift: # acceleration limits are not publicly available has_acceleration_limits: false @@ -25,9 +25,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 330.0 - max_position: 6.28318530718 - max_velocity: 2.0943951 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 elbow_joint: # acceleration limits are not publicly available has_acceleration_limits: false @@ -45,9 +45,9 @@ joint_limits: # # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for # more information. - max_position: 3.14159265359 - max_velocity: 3.14159265359 - min_position: -3.14159265359 + max_position: !degrees 180.0 + max_velocity: !degrees 180.0 + min_position: !degrees -180.0 wrist_1: # acceleration limits are not publicly available has_acceleration_limits: false @@ -55,9 +55,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_2: # acceleration limits are not publicly available has_acceleration_limits: false @@ -65,9 +65,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_3: # acceleration limits are not publicly available has_acceleration_limits: false @@ -75,6 +75,6 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 diff --git a/ur_description/config/ur10e/joint_limits.yaml b/ur_description/config/ur10e/joint_limits.yaml index 0213e8406..983a43ce1 100644 --- a/ur_description/config/ur10e/joint_limits.yaml +++ b/ur_description/config/ur10e/joint_limits.yaml @@ -15,9 +15,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 330.0 - max_position: 6.28318530718 - max_velocity: 2.0943951 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 shoulder_lift: # acceleration limits are not publicly available has_acceleration_limits: false @@ -25,9 +25,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 330.0 - max_position: 6.28318530718 - max_velocity: 2.0943951 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 elbow_joint: # acceleration limits are not publicly available has_acceleration_limits: false @@ -45,9 +45,9 @@ joint_limits: # # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for # more information. - max_position: 3.14159265359 - max_velocity: 3.14159265359 - min_position: -3.14159265359 + max_position: !degrees 180.0 + max_velocity: !degrees 180.0 + min_position: !degrees -180.0 wrist_1: # acceleration limits are not publicly available has_acceleration_limits: false @@ -55,9 +55,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_2: # acceleration limits are not publicly available has_acceleration_limits: false @@ -65,9 +65,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_3: # acceleration limits are not publicly available has_acceleration_limits: false @@ -75,6 +75,6 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 diff --git a/ur_description/config/ur16e/joint_limits.yaml b/ur_description/config/ur16e/joint_limits.yaml index 65f7d56d3..272bb4843 100644 --- a/ur_description/config/ur16e/joint_limits.yaml +++ b/ur_description/config/ur16e/joint_limits.yaml @@ -15,9 +15,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 330.0 - max_position: 6.28318530718 - max_velocity: 2.0943951 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 shoulder_lift: # acceleration limits are not publicly available has_acceleration_limits: false @@ -25,9 +25,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 330.0 - max_position: 6.28318530718 - max_velocity: 2.0943951 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 elbow_joint: # acceleration limits are not publicly available has_acceleration_limits: false @@ -45,9 +45,9 @@ joint_limits: # # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for # more information. - max_position: 3.14159265359 - max_velocity: 3.14159265359 - min_position: -3.14159265359 + max_position: !degrees 180.0 + max_velocity: !degrees 180.0 + min_position: !degrees -180.0 wrist_1: # acceleration limits are not publicly available has_acceleration_limits: false @@ -55,9 +55,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_2: # acceleration limits are not publicly available has_acceleration_limits: false @@ -65,9 +65,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_3: # acceleration limits are not publicly available has_acceleration_limits: false @@ -75,6 +75,6 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 diff --git a/ur_description/config/ur3/joint_limits.yaml b/ur_description/config/ur3/joint_limits.yaml index e0ff1150b..461288abf 100644 --- a/ur_description/config/ur3/joint_limits.yaml +++ b/ur_description/config/ur3/joint_limits.yaml @@ -15,9 +15,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 shoulder_lift: # acceleration limits are not publicly available has_acceleration_limits: false @@ -25,9 +25,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + 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 @@ -45,9 +45,9 @@ joint_limits: # # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for # more information. - max_position: 3.14159265359 - max_velocity: 3.14159265359 - min_position: -3.14159265359 + max_position: !degrees 180.0 + max_velocity: !degrees 180.0 + min_position: !degrees -180.0 wrist_1: # acceleration limits are not publicly available has_acceleration_limits: false @@ -55,9 +55,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 12.0 - max_position: 6.28318530718 - max_velocity: 6.28318530718 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 360.0 + min_position: !degrees -360.0 wrist_2: # acceleration limits are not publicly available has_acceleration_limits: false @@ -65,9 +65,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 12.0 - max_position: 6.28318530718 - max_velocity: 6.28318530718 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 360.0 + min_position: !degrees -360.0 wrist_3: # acceleration limits are not publicly available has_acceleration_limits: false @@ -75,6 +75,6 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 12.0 - max_position: 6.28318530718 - max_velocity: 6.28318530718 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 360.0 + min_position: !degrees -360.0 diff --git a/ur_description/config/ur3e/joint_limits.yaml b/ur_description/config/ur3e/joint_limits.yaml index 8d536c13b..85b6f644f 100644 --- a/ur_description/config/ur3e/joint_limits.yaml +++ b/ur_description/config/ur3e/joint_limits.yaml @@ -15,9 +15,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 shoulder_lift: # acceleration limits are not publicly available has_acceleration_limits: false @@ -25,9 +25,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 56.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + 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 @@ -45,9 +45,9 @@ joint_limits: # # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for # more information. - max_position: 3.14159265359 - max_velocity: 3.14159265359 - min_position: -3.14159265359 + max_position: !degrees 180.0 + max_velocity: !degrees 180.0 + min_position: !degrees -180.0 wrist_1: # acceleration limits are not publicly available has_acceleration_limits: false @@ -55,9 +55,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 12.0 - max_position: 6.28318530718 - max_velocity: 6.28318530718 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 360.0 + min_position: !degrees -360.0 wrist_2: # acceleration limits are not publicly available has_acceleration_limits: false @@ -65,9 +65,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 12.0 - max_position: 6.28318530718 - max_velocity: 6.28318530718 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 360.0 + min_position: !degrees -360.0 wrist_3: # acceleration limits are not publicly available has_acceleration_limits: false @@ -75,6 +75,6 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 12.0 - max_position: 6.28318530718 - max_velocity: 6.28318530718 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 360.0 + min_position: !degrees -360.0 diff --git a/ur_description/config/ur5/joint_limits.yaml b/ur_description/config/ur5/joint_limits.yaml index 493ea55ec..28eacc3d9 100644 --- a/ur_description/config/ur5/joint_limits.yaml +++ b/ur_description/config/ur5/joint_limits.yaml @@ -15,9 +15,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 150.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 shoulder_lift: # acceleration limits are not publicly available has_acceleration_limits: false @@ -25,9 +25,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 150.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + 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 @@ -45,9 +45,9 @@ joint_limits: # # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for # more information. - max_position: 3.14159265359 - max_velocity: 3.14159265359 - min_position: -3.14159265359 + max_position: !degrees 180.0 + max_velocity: !degrees 180.0 + min_position: !degrees -180.0 wrist_1: # acceleration limits are not publicly available has_acceleration_limits: false @@ -55,9 +55,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 28.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_2: # acceleration limits are not publicly available has_acceleration_limits: false @@ -65,9 +65,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 28.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_3: # acceleration limits are not publicly available has_acceleration_limits: false @@ -75,6 +75,6 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 28.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 diff --git a/ur_description/config/ur5e/joint_limits.yaml b/ur_description/config/ur5e/joint_limits.yaml index 1e2404272..dddc059a8 100644 --- a/ur_description/config/ur5e/joint_limits.yaml +++ b/ur_description/config/ur5e/joint_limits.yaml @@ -15,9 +15,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 150.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 shoulder_lift: # acceleration limits are not publicly available has_acceleration_limits: false @@ -25,9 +25,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 150.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + 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 @@ -45,9 +45,9 @@ joint_limits: # # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for # more information. - max_position: 3.14159265359 - max_velocity: 3.14159265359 - min_position: -3.14159265359 + max_position: !degrees 180.0 + max_velocity: !degrees 180.0 + min_position: !degrees -180.0 wrist_1: # acceleration limits are not publicly available has_acceleration_limits: false @@ -55,9 +55,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 28.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_2: # acceleration limits are not publicly available has_acceleration_limits: false @@ -65,9 +65,9 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 28.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0 wrist_3: # acceleration limits are not publicly available has_acceleration_limits: false @@ -75,6 +75,6 @@ joint_limits: has_position_limits: true has_velocity_limits: true max_effort: 28.0 - max_position: 6.28318530718 - max_velocity: 3.14159265359 - min_position: -6.28318530718 + max_position: !degrees 360.0 + max_velocity: !degrees 180.0 + min_position: !degrees -360.0