Skip to content

Humble #11

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 17 commits into from
Mar 19, 2025
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,7 @@ This package contains tutorials around the ROS 2 packages for Universal Robots.

## Getting started
To use the tutorials from this repository, please make sure to [install ROS
2](https://docs.ros.org/en/rolling/Installation.html) on your system. Currently, only ROS Jazzy and
Rolling are supported.
2](https://docs.ros.org/en/humble/Installation.html) on your system.

With that, please create a workspace, clone this repo into the workspace, install the dependencies
and build the workspace.
Expand Down
3 changes: 2 additions & 1 deletion my_robot_cell/my_robot_cell_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,10 @@ cmake_minimum_required(VERSION 3.8)
project(my_robot_cell_control)

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)

install(
DIRECTORY launch config urdf
DIRECTORY launch config urdf rviz
DESTINATION share/${PROJECT_NAME}
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,12 @@ controller_manager:
forward_position_controller:
type: position_controllers/JointGroupPositionController

ur_configuration_controller:
type: ur_controllers/URConfigurationController

ur_configuration_controller:
ros__parameters:
tf_prefix: "ur20_"

speed_scaling_state_broadcaster:
ros__parameters:
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
kinematics:
shoulder:
x: 0
y: 0
z: 0.23630000000000001
roll: -0
pitch: 0
yaw: -0
upper_arm:
x: 0
y: 0
z: 0
roll: 1.570796327
pitch: 0
yaw: -0
forearm:
x: -0.86199999999999999
y: 0
z: 0
roll: -0
pitch: 0
yaw: -0
wrist_1:
x: -0.72870000000000001
y: 0
z: 0.20100000000000001
roll: -0
pitch: 0
yaw: -0
wrist_2:
x: 0
y: -0.1593
z: -3.2672976162492252e-11
roll: 1.570796327
pitch: 0
yaw: -0
wrist_3:
x: 0
y: 0.15429999999999999
z: -3.1647459019915597e-11
roll: 1.5707963265897931
pitch: 3.1415926535897931
yaw: 3.1415926535897931
hash: calib_4890363623803256388
77 changes: 77 additions & 0 deletions my_robot_cell/my_robot_cell_control/config/ur20/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
# Joints limits
#
# Sources:
#
# - Universal Robots e-Series, User Manual, UR20, Version 5.14
# https://s3-eu-west-1.amazonaws.com/ur-support-site/203281/706-276-00_UR20_User_Manual_en_Global.pdf
joint_limits:
shoulder_pan_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: 738.0
max_position: !degrees 360.0
max_velocity: !degrees 120.0
min_position: !degrees -360.0
shoulder_lift_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: 738.0
max_position: !degrees 360.0
max_velocity: !degrees 120.0
min_position: !degrees -360.0
elbow_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 433.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: !degrees 180.0
max_velocity: !degrees 150.0
min_position: !degrees -180.0
wrist_1_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: 107.0
max_position: !degrees 360.0
max_velocity: !degrees 210.0
min_position: !degrees -360.0
wrist_2_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: 107.0
max_position: !degrees 360.0
max_velocity: !degrees 210.0
min_position: !degrees -360.0
wrist_3_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: 107.0
max_position: !degrees 360.0
max_velocity: !degrees 210.0
min_position: !degrees -360.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,122 @@
# Physical parameters

offsets:
shoulder_offset: 0.260 # measured from model
elbow_offset: 0.043 # measured from model

inertia_parameters:
# taken from https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/
base_mass: 4.0 # This mass might be incorrect
shoulder_mass: 16.343
upper_arm_mass: 29.632
forearm_mass: 7.879
wrist_1_mass: 3.054
wrist_2_mass: 3.126
wrist_3_mass: 0.926

shoulder_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE
upper_arm_radius: x0.054 # FROM UR5 CURRENTLY NOT USED ANYMORE
elbow_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE
forearm_radius: x0.040 # FROM UR5 CURRENTLY NOT USED ANYMORE
wrist_radius: x0.045 # FROM UR5 CURRENTLY NOT USED ANYMORE

links:
base:
radius: 0.075
length: 0.038

center_of_mass:
shoulder_cog:
x: 0.0 # model.x
y: -0.0062 # -model.z
z: -0.061 # model.y
upper_arm_cog:
x: -0.3394 # model.x - upperarm_length
y: 0.0 # model.y
z: 0.2098 # model.z
forearm_cog:
x: -0.4053 # model.x - forearm_length
y: 0.0 # model.y
z: 0.0604 # model.z
wrist_1_cog:
x: 0.0 # model.x
y: -0.0393 # -model.z
z: -0.0026 # model.y
wrist_2_cog:
x: 0.0 # model.x
y: 0.0379 # model.z
z: -0.0024 # -model.y
wrist_3_cog:
x: 0.0 # model.x
y: 0.0 # model.y
z: -0.0293 # model.z

rotation:
shoulder:
roll: 1.570796326794897
pitch: 0
yaw: 0
upper_arm:
roll: 0
pitch: 0
yaw: 0
forearm:
roll: 0
pitch: 0
yaw: 0
wrist_1:
roll: 1.570796326794897
pitch: 0
yaw: 0
wrist_2:
roll: -1.570796326794897
pitch: 0
yaw: 0
wrist_3:
roll: 0
pitch: 0
yaw: 0

tensor:
shoulder:
ixx: 0.08866
ixy: -0.00011
ixz: -0.00011
iyy: 0.07632
iyz: 0.00720
izz: 0.08418
upper_arm:
ixx: 0.14670
ixy: 0.00019
ixz: -0.05163
iyy: 4.66590
iyz: 0.00004
izz: 4.63480
forearm:
ixx: 0.02612
ixy: -0.00005
ixz: -0.02898
iyy: 0.75763
iyz: -0.00001
izz: 0.75327
wrist_1:
ixx: 0.00555
ixy: -0.00001
ixz: -0.00002
iyy: 0.00537
iyz: 0.00036
izz: 0.00402
wrist_2:
ixx: 0.00586
ixy: -0.00001
ixz: -0.00002
iyy: 0.00578
iyz: -0.00037
izz: 0.00427
wrist_3:
ixx: 0.00092
ixy: 0.0
ixz: 0.0
iyy: 0.00091
iyz: 0.0
izz: 0.00117
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
# Visualisation

mesh_files:
base:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/base.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/base.stl

shoulder:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/shoulder.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/shoulder.stl

upper_arm:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/upperarm.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/upperarm.stl
mesh_files:

forearm:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/forearm.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/forearm.stl

wrist_1:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/wrist1.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/wrist1.stl
visual_offset: -0.0775

wrist_2:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/wrist2.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/wrist2.stl
visual_offset: -0.0749

wrist_3:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/wrist3.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/wrist3.stl
visual_offset: -0.07
Loading
Loading