-
Notifications
You must be signed in to change notification settings - Fork 1k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #516 from gavanderhoorn/convert_limits_files
Use 'ros_control style' joint limit files
- Loading branch information
Showing
34 changed files
with
610 additions
and
400 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 |
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 |
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 |
This file was deleted.
Oops, something went wrong.
Oops, something went wrong.