From 29a4fa09bd011f2bc0ab34d5270844a111be11c4 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Wed, 17 Jun 2020 20:11:27 +0200 Subject: [PATCH 1/7] description: rename limit files. Bring in-line with other joint limit files. --- .../ur10/{joints_limits_parameters.yaml => joint_limits.yaml} | 0 .../ur10e/{joints_limits_parameters.yaml => joint_limits.yaml} | 0 .../ur16e/{joints_limits_parameters.yaml => joint_limits.yaml} | 0 .../ur3/{joints_limits_parameters.yaml => joint_limits.yaml} | 0 .../ur3e/{joints_limits_parameters.yaml => joint_limits.yaml} | 0 .../ur5/{joints_limits_parameters.yaml => joint_limits.yaml} | 0 .../ur5e/{joints_limits_parameters.yaml => joint_limits.yaml} | 0 7 files changed, 0 insertions(+), 0 deletions(-) rename ur_description/config/ur10/{joints_limits_parameters.yaml => joint_limits.yaml} (100%) rename ur_description/config/ur10e/{joints_limits_parameters.yaml => joint_limits.yaml} (100%) rename ur_description/config/ur16e/{joints_limits_parameters.yaml => joint_limits.yaml} (100%) rename ur_description/config/ur3/{joints_limits_parameters.yaml => joint_limits.yaml} (100%) rename ur_description/config/ur3e/{joints_limits_parameters.yaml => joint_limits.yaml} (100%) rename ur_description/config/ur5/{joints_limits_parameters.yaml => joint_limits.yaml} (100%) rename ur_description/config/ur5e/{joints_limits_parameters.yaml => joint_limits.yaml} (100%) diff --git a/ur_description/config/ur10/joints_limits_parameters.yaml b/ur_description/config/ur10/joint_limits.yaml similarity index 100% rename from ur_description/config/ur10/joints_limits_parameters.yaml rename to ur_description/config/ur10/joint_limits.yaml diff --git a/ur_description/config/ur10e/joints_limits_parameters.yaml b/ur_description/config/ur10e/joint_limits.yaml similarity index 100% rename from ur_description/config/ur10e/joints_limits_parameters.yaml rename to ur_description/config/ur10e/joint_limits.yaml diff --git a/ur_description/config/ur16e/joints_limits_parameters.yaml b/ur_description/config/ur16e/joint_limits.yaml similarity index 100% rename from ur_description/config/ur16e/joints_limits_parameters.yaml rename to ur_description/config/ur16e/joint_limits.yaml diff --git a/ur_description/config/ur3/joints_limits_parameters.yaml b/ur_description/config/ur3/joint_limits.yaml similarity index 100% rename from ur_description/config/ur3/joints_limits_parameters.yaml rename to ur_description/config/ur3/joint_limits.yaml diff --git a/ur_description/config/ur3e/joints_limits_parameters.yaml b/ur_description/config/ur3e/joint_limits.yaml similarity index 100% rename from ur_description/config/ur3e/joints_limits_parameters.yaml rename to ur_description/config/ur3e/joint_limits.yaml diff --git a/ur_description/config/ur5/joints_limits_parameters.yaml b/ur_description/config/ur5/joint_limits.yaml similarity index 100% rename from ur_description/config/ur5/joints_limits_parameters.yaml rename to ur_description/config/ur5/joint_limits.yaml diff --git a/ur_description/config/ur5e/joints_limits_parameters.yaml b/ur_description/config/ur5e/joint_limits.yaml similarity index 100% rename from ur_description/config/ur5e/joints_limits_parameters.yaml rename to ur_description/config/ur5e/joint_limits.yaml From 616e7a9eecb33e9613aa7fa0ddfc939f6ce25694 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Wed, 17 Jun 2020 20:25:59 +0200 Subject: [PATCH 2/7] description: convert joint limit files to 'ros_control format'. This allows re-using them with MoveIt and ros_control hw interfaces. --- ur_description/config/ur10/joint_limits.yaml | 88 +++++++++++++------ ur_description/config/ur10e/joint_limits.yaml | 88 +++++++++++++------ ur_description/config/ur16e/joint_limits.yaml | 88 +++++++++++++------ ur_description/config/ur3/joint_limits.yaml | 88 +++++++++++++------ ur_description/config/ur3e/joint_limits.yaml | 88 +++++++++++++------ ur_description/config/ur5/joint_limits.yaml | 88 +++++++++++++------ ur_description/config/ur5e/joint_limits.yaml | 88 +++++++++++++------ 7 files changed, 413 insertions(+), 203 deletions(-) diff --git a/ur_description/config/ur10/joint_limits.yaml b/ur_description/config/ur10/joint_limits.yaml index bdaad3343..9778c2601 100644 --- a/ur_description/config/ur10/joint_limits.yaml +++ b/ur_description/config/ur10/joint_limits.yaml @@ -7,44 +7,74 @@ # - 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: +joint_limits: shoulder_pan: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.0 + # 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: - # 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). + # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 + max_position: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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/joint_limits.yaml b/ur_description/config/ur10e/joint_limits.yaml index 57a4dc43a..0213e8406 100644 --- a/ur_description/config/ur10e/joint_limits.yaml +++ b/ur_description/config/ur10e/joint_limits.yaml @@ -7,44 +7,74 @@ # - 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: +joint_limits: shoulder_pan: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.0 + # 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: - # 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). + # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 + max_position: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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/joint_limits.yaml b/ur_description/config/ur16e/joint_limits.yaml index 2a78995b6..65f7d56d3 100644 --- a/ur_description/config/ur16e/joint_limits.yaml +++ b/ur_description/config/ur16e/joint_limits.yaml @@ -7,44 +7,74 @@ # - 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: +joint_limits: shoulder_pan: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 2.0943951 - effort: 330.0 + # 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: - # 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). + # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 + max_position: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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/ur3/joint_limits.yaml b/ur_description/config/ur3/joint_limits.yaml index 08c7dc4e5..e0ff1150b 100644 --- a/ur_description/config/ur3/joint_limits.yaml +++ b/ur_description/config/ur3/joint_limits.yaml @@ -7,44 +7,74 @@ # - 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: +joint_limits: shoulder_pan: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - # 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). + # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 28.0 + max_position: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 + # 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/joint_limits.yaml b/ur_description/config/ur3e/joint_limits.yaml index 2b4564b59..8d536c13b 100644 --- a/ur_description/config/ur3e/joint_limits.yaml +++ b/ur_description/config/ur3e/joint_limits.yaml @@ -7,44 +7,74 @@ # - 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: +joint_limits: shoulder_pan: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 56.0 + # 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: - # 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). + # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 28.0 + max_position: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 6.28318530718 - effort: 12.0 + # 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/ur5/joint_limits.yaml b/ur_description/config/ur5/joint_limits.yaml index e420f5f11..493ea55ec 100644 --- a/ur_description/config/ur5/joint_limits.yaml +++ b/ur_description/config/ur5/joint_limits.yaml @@ -7,44 +7,74 @@ # - 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: +joint_limits: shoulder_pan: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 150.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 150.0 + # 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: - # 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). + # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 + max_position: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 + # 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/joint_limits.yaml b/ur_description/config/ur5e/joint_limits.yaml index 0f0e3f73d..1e2404272 100644 --- a/ur_description/config/ur5e/joint_limits.yaml +++ b/ur_description/config/ur5e/joint_limits.yaml @@ -7,44 +7,74 @@ # - 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: +joint_limits: shoulder_pan: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 150.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 150.0 + # 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: - # 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). + # 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. - lower: -3.14159265359 - upper: 3.14159265359 - velocity: 3.14159265359 - effort: 150.0 + max_position: 3.14159265359 + max_velocity: 3.14159265359 + min_position: -3.14159265359 wrist_1: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 + # 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: - lower: -6.28318530718 - upper: 6.28318530718 - velocity: 3.14159265359 - effort: 28.0 + # 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 From ba5ac32299fcbe0a6fd7ca00ae1fa98046b2c59f Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Wed, 17 Jun 2020 20:59:57 +0200 Subject: [PATCH 3/7] description: load new joint limit files. --- ur_description/launch/load_ur10.launch | 2 +- ur_description/launch/load_ur10e.launch | 2 +- ur_description/launch/load_ur16e.launch | 2 +- ur_description/launch/load_ur3.launch | 2 +- ur_description/launch/load_ur3e.launch | 2 +- ur_description/launch/load_ur5.launch | 2 +- ur_description/launch/load_ur5e.launch | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/ur_description/launch/load_ur10.launch b/ur_description/launch/load_ur10.launch index 8c2151adf..1586bd8f9 100644 --- a/ur_description/launch/load_ur10.launch +++ b/ur_description/launch/load_ur10.launch @@ -1,7 +1,7 @@ - + diff --git a/ur_description/launch/load_ur10e.launch b/ur_description/launch/load_ur10e.launch index 00edc27b1..29c7825c0 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..8a729b19f 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..298121c67 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..e72da7e18 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..86e709c19 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..06d347de3 100644 --- a/ur_description/launch/load_ur5e.launch +++ b/ur_description/launch/load_ur5e.launch @@ -1,7 +1,7 @@ - + From c86d01566971ed35a4857586cf894094428c8e09 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Wed, 17 Jun 2020 21:18:45 +0200 Subject: [PATCH 4/7] description: they're joint limits. Not joints limits. --- ur_description/launch/load_ur.launch | 4 ++-- ur_description/launch/load_ur10.launch | 2 +- ur_description/launch/load_ur10e.launch | 2 +- ur_description/launch/load_ur16e.launch | 2 +- ur_description/launch/load_ur3.launch | 2 +- ur_description/launch/load_ur3e.launch | 2 +- ur_description/launch/load_ur5.launch | 2 +- ur_description/launch/load_ur5e.launch | 2 +- ur_description/urdf/inc/ur_common.xacro | 4 ++-- ur_description/urdf/ur.xacro | 4 ++-- ur_description/urdf/ur_macro.xacro | 4 ++-- 11 files changed, 15 insertions(+), 15 deletions(-) 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 29c7825c0..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 8a729b19f..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 298121c67..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 e72da7e18..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 86e709c19..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 06d347de3..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..71eadf027 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. --> - - + + 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 @@ From 0c7538eb5e7084ee7a37a2369b46e5937cf07b17 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Wed, 17 Jun 2020 21:19:32 +0200 Subject: [PATCH 5/7] description: load values from new params. 'ros_control format' uses different names, so use them. --- ur_description/urdf/inc/ur_common.xacro | 50 ++++++++++++------------- 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/ur_description/urdf/inc/ur_common.xacro b/ur_description/urdf/inc/ur_common.xacro index 71eadf027..33bc54ecd 100644 --- a/ur_description/urdf/inc/ur_common.xacro +++ b/ur_description/urdf/inc/ur_common.xacro @@ -28,7 +28,7 @@ and as such should be considered to be for internal use only. --> - + @@ -36,30 +36,30 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + From f7af7aff3b94729e1c8ca8748830aae343766a62 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Thu, 18 Jun 2020 13:44:49 +0200 Subject: [PATCH 6/7] gazebo: update joint limit filename references. They were renamed (in c0f71ebb), so use the new names. --- ur_gazebo/launch/ur10.launch | 2 +- ur_gazebo/launch/ur10e.launch | 2 +- ur_gazebo/launch/ur16e.launch | 2 +- ur_gazebo/launch/ur3.launch | 2 +- ur_gazebo/launch/ur3e.launch | 2 +- ur_gazebo/launch/ur5.launch | 2 +- ur_gazebo/launch/ur5e.launch | 2 +- ur_gazebo/urdf/ur_robot.urdf.xacro | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) 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..8c509a5e9 100644 --- a/ur_gazebo/urdf/ur_robot.urdf.xacro +++ b/ur_gazebo/urdf/ur_robot.urdf.xacro @@ -3,7 +3,7 @@ name="ur" > - + From cbe4c86e48b696af3e14b105ae8cbb4af0eb16d7 Mon Sep 17 00:00:00 2001 From: gavanderhoorn Date: Thu, 18 Jun 2020 14:04:05 +0200 Subject: [PATCH 7/7] gazebo: use new arg names for joint limits. Renamed in ur_description, so use the new names here as well and pass the right values. --- ur_gazebo/urdf/ur_robot.urdf.xacro | 4 ++-- ur_gazebo/urdf/ur_robot_gazebo.macro.xacro | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ur_gazebo/urdf/ur_robot.urdf.xacro b/ur_gazebo/urdf/ur_robot.urdf.xacro index 8c509a5e9..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 @@ - - -