Skip to content
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

Add Ur16e support #477

Merged
merged 4 commits into from
Jun 6, 2020
Merged
Show file tree
Hide file tree
Changes from all 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
44 changes: 44 additions & 0 deletions ur_description/config/ur16e/default_kinematics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
kinematics:
shoulder:
x: 0
y: 0
z: 0.1807
roll: -0
pitch: 0
yaw: -0
upper_arm:
x: 0
y: 0
z: 0
roll: 1.570796327
pitch: 0
yaw: -0
forearm:
x: -0.4784
y: 0
z: 0
roll: -0
pitch: 0
yaw: -0
wrist_1:
x: -0.36
y: 0
z: 0.17415
roll: -0
pitch: 0
yaw: -0
wrist_2:
x: 0
y: -0.11985
z: -2.458164590756244e-11
roll: 1.570796327
pitch: 0
yaw: -0
wrist_3:
x: 0
y: 0.11655
z: -2.390480459346185e-11
roll: 1.570796326589793
pitch: 3.141592653589793
yaw: 3.141592653589793
hash: calib_1935737212149401527
34 changes: 34 additions & 0 deletions ur_description/config/ur16e/joints_limits_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# Joints limits
# According to https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/max-joint-torques-17260/
# and ur16e fact sheet (e.g. https://cdn2.hubspot.net/hubfs/4316198/1_VENDOR-LITERATURE/Universal%20Robots/UR16e/UR16e_Fact%20Sheet_(2sided).pdf)
limits:
shoulder_pan:
lower: -6.28318530718
upper: 6.28318530718
velocity: 2.094
effort: 330.0
shoulder_lift:
lower: -6.28318530718
upper: 6.28318530718
velocity: 2.094
effort: 330.0
elbow_joint:
lower: -6.28318530718
upper: 6.28318530718
velocity: 3.141
effort: 150.0
wrist_1:
lower: -6.28318530718
upper: 6.28318530718
velocity: 3.141
effort: 56.0
wrist_2:
lower: -6.28318530718
upper: 6.28318530718
velocity: 3.141
effort: 56.0
wrist_3:
lower: -6.28318530718
upper: 6.28318530718
velocity: 3.141
effort: 56.0
80 changes: 80 additions & 0 deletions ur_description/config/ur16e/physical_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
# Physical parameters

# from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/
dh_parameters:
d1: 0.1807
a2: -0.4784
a3: -0.36
d4: 0.17415
d5: 0.11985
d6: 0.11655

offsets:
shoulder_offset: 0.176 # measured from model
elbow_offset: 0.040 # measured from model

inertia_parameters:
# taken from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/
base_mass: 4.0 # This mass might be incorrect
shoulder_mass: 7.369
upper_arm_mass: 10.450
upper_arm_inertia_offset: 0.175 # measured from model
forearm_mass: 4.321
wrist_1_mass: 2.180
wrist_2_mass: 2.033
wrist_3_mass: 0.907

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
shoulder:
radius: 0.075
length: 0.178
upperarm:
radius: 0.075
length: 0.4784
forearm:
radius: 0.075
length: 0.36
wrist_1:
radius: 0.075
length: 0.12
wrist_2:
radius: 0.075
length: 0.12
wrist_3:
radius: 0.045
length: 0.05

center_of_mass: # Adjusted manually
shoulder_cog:
x: 0.0
y: 0.00244
z: -0.037
upper_arm_cog:
x: 0.00001
y: 0.15061
z: 0.38757
forearm_cog:
x: -0.00012
y: 0.06112
z: 0.1984
wrist_1_cog:
x: -0.00021
y: -0.00112
z: 0.02269
wrist_2_cog:
x: -0.00021
y: 0.00112
z: 0.002269
wrist_3_cog:
x: 0.0
y: -0.001156
z: -0.00149
70 changes: 70 additions & 0 deletions ur_description/config/ur16e/visual_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
# Visualisation
# UR16e uses the same parts as UR10e except the upper and lower arm are shortened

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

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

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

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

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

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

wrist_3:
visual:
mesh: "package://ur_description/meshes/ur10e/visual/wrist3.dae"
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh: "package://ur_description/meshes/ur10e/collision/wrist3.stl"
visual_offset: -0.1168
24 changes: 24 additions & 0 deletions ur_description/launch/ur16e_upload.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<?xml version="1.0"?>
<launch>
<!--ur10e parameters files -->
<arg name="joints_limits_params" default="$(find ur_description)/config/ur16e/joints_limits_parameters.yaml"/>
<arg name="kinematics_params" default="$(find ur_description)/config/ur16e/default_kinematics.yaml"/>
<arg name="physical_params" default="$(find ur_description)/config/ur16e/physical_parameters.yaml"/>
<arg name="visual_params" default="$(find ur_description)/config/ur16e/visual_parameters.yaml"/>
<!--common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />

<include file="$(find ur_description)/launch/ur_common.launch">
<arg name="joints_limits_params" value="$(arg joints_limits_params)"/>
<arg name="kinematics_params" value="$(arg kinematics_params)"/>
<arg name="physical_params" value="$(arg physical_params)"/>
<arg name="visual_params" value="$(arg visual_params)"/>
<arg name="transmission_hw_interface" value="$(arg transmission_hw_interface)"/>
<arg name="safety_limits" value="$(arg safety_limits)"/>
<arg name="safety_pos_margin" value="$(arg safety_pos_margin)"/>
<arg name="safety_k_position" value="$(arg safety_k_position)"/>
</include>
</launch>
10 changes: 10 additions & 0 deletions ur_description/launch/view_ur16e.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<?xml version="1.0"?>
<launch>
<include file="$(find ur_description)/launch/ur16e_upload.launch"/>

<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >
<param name="use_gui" value="true"/>
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find ur_description)/cfg/view_robot.rviz" required="true" />
</launch>
Binary file added ur_description/meshes/ur16e/collision/forearm.stl
Binary file not shown.
Binary file not shown.
Loading