diff --git a/ur_description/config/ur10/joint_limits.yaml b/ur_description/config/ur10/joint_limits.yaml new file mode 100644 index 000000000..9778c2601 --- /dev/null +++ b/ur_description/config/ur10/joint_limits.yaml @@ -0,0 +1,80 @@ +# 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 +joint_limits: + shoulder_pan: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 330.0 + max_position: 6.28318530718 + max_velocity: 2.0943951 + min_position: -6.28318530718 + shoulder_lift: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 330.0 + max_position: 6.28318530718 + max_velocity: 2.0943951 + min_position: -6.28318530718 + 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: 150.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: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 + wrist_1: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_2: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_3: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 diff --git a/ur_description/config/ur10/joints_limits_parameters.yaml b/ur_description/config/ur10/joints_limits_parameters.yaml deleted file mode 100644 index bdaad3343..000000000 --- a/ur_description/config/ur10/joints_limits_parameters.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# 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.0943951 - effort: 330.0 - shoulder_lift: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.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 - # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 - wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 - wrist_2: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 - wrist_3: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 diff --git a/ur_description/config/ur10e/joint_limits.yaml b/ur_description/config/ur10e/joint_limits.yaml new file mode 100644 index 000000000..0213e8406 --- /dev/null +++ b/ur_description/config/ur10e/joint_limits.yaml @@ -0,0 +1,80 @@ +# 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 +joint_limits: + shoulder_pan: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 330.0 + max_position: 6.28318530718 + max_velocity: 2.0943951 + min_position: -6.28318530718 + shoulder_lift: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 330.0 + max_position: 6.28318530718 + max_velocity: 2.0943951 + min_position: -6.28318530718 + 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: 150.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: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 + wrist_1: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_2: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_3: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 diff --git a/ur_description/config/ur10e/joints_limits_parameters.yaml b/ur_description/config/ur10e/joints_limits_parameters.yaml deleted file mode 100644 index 57a4dc43a..000000000 --- a/ur_description/config/ur10e/joints_limits_parameters.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# 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.0943951 - effort: 330.0 - shoulder_lift: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.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 - # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 - wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 - wrist_2: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 - wrist_3: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 diff --git a/ur_description/config/ur16e/joint_limits.yaml b/ur_description/config/ur16e/joint_limits.yaml new file mode 100644 index 000000000..65f7d56d3 --- /dev/null +++ b/ur_description/config/ur16e/joint_limits.yaml @@ -0,0 +1,80 @@ +# Joints limits +# +# 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 +joint_limits: + shoulder_pan: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 330.0 + max_position: 6.28318530718 + max_velocity: 2.0943951 + min_position: -6.28318530718 + shoulder_lift: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 330.0 + max_position: 6.28318530718 + max_velocity: 2.0943951 + min_position: -6.28318530718 + 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: 150.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: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 + wrist_1: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_2: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_3: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 diff --git a/ur_description/config/ur16e/joints_limits_parameters.yaml b/ur_description/config/ur16e/joints_limits_parameters.yaml deleted file mode 100644 index 2a78995b6..000000000 --- a/ur_description/config/ur16e/joints_limits_parameters.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# Joints limits -# -# 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.0943951 - effort: 330.0 - shoulder_lift: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.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 - # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 - wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 - wrist_2: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 - wrist_3: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 diff --git a/ur_description/config/ur3/joint_limits.yaml b/ur_description/config/ur3/joint_limits.yaml new file mode 100644 index 000000000..e0ff1150b --- /dev/null +++ b/ur_description/config/ur3/joint_limits.yaml @@ -0,0 +1,80 @@ +# 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 +joint_limits: + shoulder_pan: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + shoulder_lift: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + 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: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 + wrist_1: + # 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: 6.28318530718 + max_velocity: 6.28318530718 + min_position: -6.28318530718 + wrist_2: + # 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: 6.28318530718 + max_velocity: 6.28318530718 + min_position: -6.28318530718 + wrist_3: + # 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: 6.28318530718 + max_velocity: 6.28318530718 + min_position: -6.28318530718 diff --git a/ur_description/config/ur3/joints_limits_parameters.yaml b/ur_description/config/ur3/joints_limits_parameters.yaml deleted file mode 100644 index 08c7dc4e5..000000000 --- a/ur_description/config/ur3/joints_limits_parameters.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# 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: 3.14159265359 - effort: 56.0 - shoulder_lift: - lower: -6.28318530718 - upper: 6.28318530718 - 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 - # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 28.0 - wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 - wrist_2: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 - wrist_3: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 diff --git a/ur_description/config/ur3e/joint_limits.yaml b/ur_description/config/ur3e/joint_limits.yaml new file mode 100644 index 000000000..8d536c13b --- /dev/null +++ b/ur_description/config/ur3e/joint_limits.yaml @@ -0,0 +1,80 @@ +# 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: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + shoulder_lift: + # 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: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + 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: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 + wrist_1: + # 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: 6.28318530718 + max_velocity: 6.28318530718 + min_position: -6.28318530718 + wrist_2: + # 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: 6.28318530718 + max_velocity: 6.28318530718 + min_position: -6.28318530718 + wrist_3: + # 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: 6.28318530718 + max_velocity: 6.28318530718 + min_position: -6.28318530718 diff --git a/ur_description/config/ur3e/joints_limits_parameters.yaml b/ur_description/config/ur3e/joints_limits_parameters.yaml deleted file mode 100644 index 2b4564b59..000000000 --- a/ur_description/config/ur3e/joints_limits_parameters.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# 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: 3.14159265359 - effort: 56.0 - shoulder_lift: - lower: -6.28318530718 - upper: 6.28318530718 - 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 - # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 28.0 - wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 - wrist_2: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 - wrist_3: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 diff --git a/ur_description/config/ur5/joint_limits.yaml b/ur_description/config/ur5/joint_limits.yaml new file mode 100644 index 000000000..493ea55ec --- /dev/null +++ b/ur_description/config/ur5/joint_limits.yaml @@ -0,0 +1,80 @@ +# 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 +joint_limits: + shoulder_pan: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 150.0 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + shoulder_lift: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 150.0 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + 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: 150.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: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 + wrist_1: + # 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 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_2: + # 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 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_3: + # 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 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 diff --git a/ur_description/config/ur5/joints_limits_parameters.yaml b/ur_description/config/ur5/joints_limits_parameters.yaml deleted file mode 100644 index e420f5f11..000000000 --- a/ur_description/config/ur5/joints_limits_parameters.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# 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: 3.14159265359 - effort: 150.0 - shoulder_lift: - lower: -6.28318530718 - upper: 6.28318530718 - 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 - # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 - wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 - wrist_2: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 - wrist_3: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 diff --git a/ur_description/config/ur5e/joint_limits.yaml b/ur_description/config/ur5e/joint_limits.yaml new file mode 100644 index 000000000..1e2404272 --- /dev/null +++ b/ur_description/config/ur5e/joint_limits.yaml @@ -0,0 +1,80 @@ +# 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 +joint_limits: + shoulder_pan: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 150.0 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + shoulder_lift: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 150.0 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + 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: 150.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: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 + wrist_1: + # 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 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_2: + # 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 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 + wrist_3: + # 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 + max_position: 6.28318530718 + max_velocity: 3.14159265359 + min_position: -6.28318530718 diff --git a/ur_description/config/ur5e/joints_limits_parameters.yaml b/ur_description/config/ur5e/joints_limits_parameters.yaml deleted file mode 100644 index 0f0e3f73d..000000000 --- a/ur_description/config/ur5e/joints_limits_parameters.yaml +++ /dev/null @@ -1,50 +0,0 @@ -# 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: 3.14159265359 - effort: 150.0 - shoulder_lift: - lower: -6.28318530718 - upper: 6.28318530718 - 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 - # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 - wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 - wrist_2: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 - wrist_3: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 diff --git a/ur_description/launch/load_ur.launch b/ur_description/launch/load_ur.launch index 92214fd74..3e459dd52 100644 --- a/ur_description/launch/load_ur.launch +++ b/ur_description/launch/load_ur.launch @@ -1,7 +1,7 @@ - + @@ -29,7 +29,7 @@ to load it onto the parameter server. --> - + diff --git a/ur_description/launch/load_ur10e.launch b/ur_description/launch/load_ur10e.launch index 00edc27b1..6c72e0b62 100644 --- a/ur_description/launch/load_ur10e.launch +++ b/ur_description/launch/load_ur10e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_description/launch/load_ur16e.launch b/ur_description/launch/load_ur16e.launch index 4c17cd956..a633e4c1b 100644 --- a/ur_description/launch/load_ur16e.launch +++ b/ur_description/launch/load_ur16e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_description/launch/load_ur3.launch b/ur_description/launch/load_ur3.launch index 4766180fc..395545f90 100644 --- a/ur_description/launch/load_ur3.launch +++ b/ur_description/launch/load_ur3.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_description/launch/load_ur3e.launch b/ur_description/launch/load_ur3e.launch index 1e2dcac0b..2567cb95d 100644 --- a/ur_description/launch/load_ur3e.launch +++ b/ur_description/launch/load_ur3e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_description/launch/load_ur5.launch b/ur_description/launch/load_ur5.launch index 74365ce26..aa5be93ae 100644 --- a/ur_description/launch/load_ur5.launch +++ b/ur_description/launch/load_ur5.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_description/launch/load_ur5e.launch b/ur_description/launch/load_ur5e.launch index 69cfa5e0f..b9368d1da 100644 --- a/ur_description/launch/load_ur5e.launch +++ b/ur_description/launch/load_ur5e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_description/urdf/inc/ur_common.xacro b/ur_description/urdf/inc/ur_common.xacro index 6846968b9..33bc54ecd 100644 --- a/ur_description/urdf/inc/ur_common.xacro +++ b/ur_description/urdf/inc/ur_common.xacro @@ -27,8 +27,8 @@ This macro is NOT part of the public API of the ur_description pkg, and as such should be considered to be for internal use only. --> - - + + @@ -36,30 +36,30 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur_description/urdf/ur.xacro b/ur_description/urdf/ur.xacro index 9f55e1451..dadf5aa80 100644 --- a/ur_description/urdf/ur.xacro +++ b/ur_description/urdf/ur.xacro @@ -5,7 +5,7 @@ - + @@ -22,7 +22,7 @@ diff --git a/ur_gazebo/launch/ur10.launch b/ur_gazebo/launch/ur10.launch index 5674291a0..5ef1622d8 100644 --- a/ur_gazebo/launch/ur10.launch +++ b/ur_gazebo/launch/ur10.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_gazebo/launch/ur10e.launch b/ur_gazebo/launch/ur10e.launch index 21df8cd9c..4fa2a9d5c 100644 --- a/ur_gazebo/launch/ur10e.launch +++ b/ur_gazebo/launch/ur10e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_gazebo/launch/ur16e.launch b/ur_gazebo/launch/ur16e.launch index 8fd2d5063..d8da8b358 100644 --- a/ur_gazebo/launch/ur16e.launch +++ b/ur_gazebo/launch/ur16e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_gazebo/launch/ur3.launch b/ur_gazebo/launch/ur3.launch index 3ded46cb6..5cd48afec 100644 --- a/ur_gazebo/launch/ur3.launch +++ b/ur_gazebo/launch/ur3.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_gazebo/launch/ur3e.launch b/ur_gazebo/launch/ur3e.launch index 525952b33..7acbc1e7d 100644 --- a/ur_gazebo/launch/ur3e.launch +++ b/ur_gazebo/launch/ur3e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_gazebo/launch/ur5.launch b/ur_gazebo/launch/ur5.launch index 8c45d5377..7fc1f349a 100644 --- a/ur_gazebo/launch/ur5.launch +++ b/ur_gazebo/launch/ur5.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_gazebo/launch/ur5e.launch b/ur_gazebo/launch/ur5e.launch index 9c9017609..88c0d766c 100644 --- a/ur_gazebo/launch/ur5e.launch +++ b/ur_gazebo/launch/ur5e.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_gazebo/urdf/ur_robot.urdf.xacro b/ur_gazebo/urdf/ur_robot.urdf.xacro index 3fb327a78..07a99e1e2 100644 --- a/ur_gazebo/urdf/ur_robot.urdf.xacro +++ b/ur_gazebo/urdf/ur_robot.urdf.xacro @@ -3,7 +3,7 @@ name="ur" > - + @@ -17,7 +17,7 @@ - - -