From 8f7c90d0f8b5b1ca793318f250f6d4670345f4cc Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Tue, 16 Jun 2020 22:22:15 +0200 Subject: [PATCH] description: correct joint limits for all supported variants. Based on values from the User Manuals. --- .../config/ur10/joints_limits_parameters.yaml | 26 ++++++++++----- .../ur10e/joints_limits_parameters.yaml | 26 ++++++++++----- .../ur16e/joints_limits_parameters.yaml | 22 ++++++++----- .../config/ur3/joints_limits_parameters.yaml | 33 +++++++++++-------- .../config/ur3e/joints_limits_parameters.yaml | 33 +++++++++++-------- .../config/ur5/joints_limits_parameters.yaml | 31 ++++++++++------- .../config/ur5e/joints_limits_parameters.yaml | 31 ++++++++++------- 7 files changed, 126 insertions(+), 76 deletions(-) diff --git a/ur_description/config/ur10/joints_limits_parameters.yaml b/ur_description/config/ur10/joints_limits_parameters.yaml index 9b51eb29a..bdaad3343 100644 --- a/ur_description/config/ur10/joints_limits_parameters.yaml +++ b/ur_description/config/ur10/joints_limits_parameters.yaml @@ -1,14 +1,22 @@ # Joints limits +# +# Sources: +# +# - UR10 User Manual, Universal Robots, UR10/CB3, Version 3.13 +# https://s3-eu-west-1.amazonaws.com/ur-support-site/69442/99203_UR10_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 limits: shoulder_pan: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 + velocity: 2.0943951 effort: 330.0 shoulder_lift: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 + velocity: 2.0943951 effort: 330.0 elbow_joint: # we artificially limit this joint to half it's actual joint limit to avoid @@ -23,20 +31,20 @@ limits: # more information. lower: -3.14159265359 upper: 3.14159265359 - velocity: 3.15 + velocity: 3.14159265359 effort: 150.0 wrist_1: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 56.0 wrist_2: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 56.0 wrist_3: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 \ No newline at end of file + velocity: 3.14159265359 + effort: 56.0 diff --git a/ur_description/config/ur10e/joints_limits_parameters.yaml b/ur_description/config/ur10e/joints_limits_parameters.yaml index 9b51eb29a..57a4dc43a 100644 --- a/ur_description/config/ur10e/joints_limits_parameters.yaml +++ b/ur_description/config/ur10e/joints_limits_parameters.yaml @@ -1,14 +1,22 @@ # Joints limits +# +# Sources: +# +# - Universal Robots e-Series, User Manual, UR10e, Version 5.8 +# https://s3-eu-west-1.amazonaws.com/ur-support-site/69139/99405_UR10e_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 limits: shoulder_pan: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 + velocity: 2.0943951 effort: 330.0 shoulder_lift: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 + velocity: 2.0943951 effort: 330.0 elbow_joint: # we artificially limit this joint to half it's actual joint limit to avoid @@ -23,20 +31,20 @@ limits: # more information. lower: -3.14159265359 upper: 3.14159265359 - velocity: 3.15 + velocity: 3.14159265359 effort: 150.0 wrist_1: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 56.0 wrist_2: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 56.0 wrist_3: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 \ No newline at end of file + velocity: 3.14159265359 + effort: 56.0 diff --git a/ur_description/config/ur16e/joints_limits_parameters.yaml b/ur_description/config/ur16e/joints_limits_parameters.yaml index 6502c03bf..2a78995b6 100644 --- a/ur_description/config/ur16e/joints_limits_parameters.yaml +++ b/ur_description/config/ur16e/joints_limits_parameters.yaml @@ -1,16 +1,22 @@ # Joints limits -# According to https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/max-joint-torques-17260/ -# and ur16e fact sheet (e.g. https://cdn2.hubspot.net/hubfs/4316198/1_VENDOR-LITERATURE/Universal%20Robots/UR16e/UR16e_Fact%20Sheet_(2sided).pdf) +# +# Sources: +# +# - Universal Robots e-Series, User Manual, UR16e, Version 5.8 +# https://s3-eu-west-1.amazonaws.com/ur-support-site/69187/99473_UR16e_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 limits: shoulder_pan: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.094 + velocity: 2.0943951 effort: 330.0 shoulder_lift: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.094 + velocity: 2.0943951 effort: 330.0 elbow_joint: # we artificially limit this joint to half it's actual joint limit to avoid @@ -25,20 +31,20 @@ limits: # more information. lower: -3.14159265359 upper: 3.14159265359 - velocity: 3.141 + velocity: 3.14159265359 effort: 150.0 wrist_1: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.141 + velocity: 3.14159265359 effort: 56.0 wrist_2: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.141 + velocity: 3.14159265359 effort: 56.0 wrist_3: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.141 + velocity: 3.14159265359 effort: 56.0 diff --git a/ur_description/config/ur3/joints_limits_parameters.yaml b/ur_description/config/ur3/joints_limits_parameters.yaml index acac1a420..08c7dc4e5 100644 --- a/ur_description/config/ur3/joints_limits_parameters.yaml +++ b/ur_description/config/ur3/joints_limits_parameters.yaml @@ -1,16 +1,23 @@ # Joints limits - +# +# Sources: +# +# - UR3 User Manual, Universal Robots, UR3/CB3, Version 3.13 +# https://s3-eu-west-1.amazonaws.com/ur-support-site/69300/99241_UR3_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 limits: shoulder_pan: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 56.0 shoulder_lift: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 56.0 elbow_joint: # we artificially limit this joint to half it's actual joint limit to avoid # (MoveIt/OMPL) planning problems, as due to the physical construction of @@ -24,20 +31,20 @@ limits: # more information. lower: -3.14159265359 upper: 3.14159265359 - velocity: 3.15 - effort: 150.0 + velocity: 3.14159265359 + effort: 28.0 wrist_1: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 6.28318530718 + effort: 12.0 wrist_2: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 6.28318530718 + effort: 12.0 wrist_3: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 \ No newline at end of file + velocity: 6.28318530718 + effort: 12.0 diff --git a/ur_description/config/ur3e/joints_limits_parameters.yaml b/ur_description/config/ur3e/joints_limits_parameters.yaml index acac1a420..2b4564b59 100644 --- a/ur_description/config/ur3e/joints_limits_parameters.yaml +++ b/ur_description/config/ur3e/joints_limits_parameters.yaml @@ -1,16 +1,23 @@ # 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 limits: shoulder_pan: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 56.0 shoulder_lift: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 56.0 elbow_joint: # we artificially limit this joint to half it's actual joint limit to avoid # (MoveIt/OMPL) planning problems, as due to the physical construction of @@ -24,20 +31,20 @@ limits: # more information. lower: -3.14159265359 upper: 3.14159265359 - velocity: 3.15 - effort: 150.0 + velocity: 3.14159265359 + effort: 28.0 wrist_1: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 6.28318530718 + effort: 12.0 wrist_2: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 6.28318530718 + effort: 12.0 wrist_3: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 \ No newline at end of file + velocity: 6.28318530718 + effort: 12.0 diff --git a/ur_description/config/ur5/joints_limits_parameters.yaml b/ur_description/config/ur5/joints_limits_parameters.yaml index acac1a420..e420f5f11 100644 --- a/ur_description/config/ur5/joints_limits_parameters.yaml +++ b/ur_description/config/ur5/joints_limits_parameters.yaml @@ -1,16 +1,23 @@ # Joints limits - +# +# Sources: +# +# - UR5 User Manual, Universal Robots, UR5/CB3, Version 3.13 +# https://s3-eu-west-1.amazonaws.com/ur-support-site/69371/99202_UR5_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 limits: shoulder_pan: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 150.0 shoulder_lift: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 150.0 elbow_joint: # we artificially limit this joint to half it's actual joint limit to avoid # (MoveIt/OMPL) planning problems, as due to the physical construction of @@ -24,20 +31,20 @@ limits: # more information. lower: -3.14159265359 upper: 3.14159265359 - velocity: 3.15 + velocity: 3.14159265359 effort: 150.0 wrist_1: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 28.0 wrist_2: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 28.0 wrist_3: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 \ No newline at end of file + velocity: 3.14159265359 + effort: 28.0 diff --git a/ur_description/config/ur5e/joints_limits_parameters.yaml b/ur_description/config/ur5e/joints_limits_parameters.yaml index acac1a420..0f0e3f73d 100644 --- a/ur_description/config/ur5e/joints_limits_parameters.yaml +++ b/ur_description/config/ur5e/joints_limits_parameters.yaml @@ -1,16 +1,23 @@ # Joints limits - +# +# Sources: +# +# - Universal Robots e-Series, User Manual, UR5e, Version 5.8 +# https://s3-eu-west-1.amazonaws.com/ur-support-site/69091/99404_UR5e_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 limits: shoulder_pan: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 150.0 shoulder_lift: lower: -6.28318530718 upper: 6.28318530718 - velocity: 2.16 - effort: 330.0 + velocity: 3.14159265359 + effort: 150.0 elbow_joint: # we artificially limit this joint to half it's actual joint limit to avoid # (MoveIt/OMPL) planning problems, as due to the physical construction of @@ -24,20 +31,20 @@ limits: # more information. lower: -3.14159265359 upper: 3.14159265359 - velocity: 3.15 + velocity: 3.14159265359 effort: 150.0 wrist_1: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 28.0 wrist_2: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 + velocity: 3.14159265359 + effort: 28.0 wrist_3: lower: -6.28318530718 upper: 6.28318530718 - velocity: 3.2 - effort: 54.0 \ No newline at end of file + velocity: 3.14159265359 + effort: 28.0