Skip to content

Commit c0be627

Browse files
author
Felix Exner (fexner)
authored
Merge pull request #114 from fmauch/remove_ros2_control
Remove ros2_control tag from package (and move it to ur_robot_driver)
2 parents 4e352ce + 059f026 commit c0be627

File tree

9 files changed

+253
-506
lines changed

9 files changed

+253
-506
lines changed

README.md

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -81,3 +81,11 @@ parameters file.
8181
As mentioned above, see the `urdf/ur.urdf.xacro` file as an example to integrate a UR robot into
8282
your scene description. Basically, you could create a copy of that file and extend it with the
8383
modifications from your specific scene.
84+
85+
### Using description with ros2_control
86+
The description itself does not contain a `ros2_control` tag. However, the package provides a couple
87+
of helper files to create your own `ros2_control` tag describing the robot's joint control
88+
mechanisms. See the [`urdf/ur_mocked.urdf.xacro`](urdf/ur_mocked.urdf.xacro)
89+
file as an example using [mock
90+
hardware](https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/mock_components_userdoc.html)
91+
to control the robot.

test/test_ur_urdf_xacro.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,20 +32,23 @@
3232
import shutil
3333
import subprocess
3434
import tempfile
35+
import pytest
3536

3637
from ament_index_python.packages import get_package_share_directory
3738

3839

39-
def test_ur_urdf_xacro():
40+
@pytest.mark.parametrize(
41+
"ur_type", ["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"]
42+
)
43+
@pytest.mark.parametrize("description_file", ["ur.urdf.xacro", "ur_mocked.urdf.xacro"])
44+
@pytest.mark.parametrize("prefix", ["", "my_ur_"])
45+
def test_ur_urdf_xacro(ur_type, description_file, prefix):
4046
# Initialize Arguments
41-
ur_type = "ur3"
4247
safety_limits = "true"
4348
safety_pos_margin = "0.15"
4449
safety_k_position = "20"
4550
# General Arguments
4651
description_package = "ur_description"
47-
description_file = "ur.urdf.xacro"
48-
prefix = '""'
4952

5053
joint_limit_params = os.path.join(
5154
get_package_share_directory(description_package), "config", ur_type, "joint_limits.yaml"

urdf/inc/ur_joint_control.xacro

Lines changed: 128 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,128 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://wiki.ros.org/xacro">
3+
<xacro:macro name="ur_joint_control_description" params="
4+
tf_prefix
5+
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
6+
">
7+
<joint name="${tf_prefix}shoulder_pan_joint">
8+
<command_interface name="position">
9+
<param name="min">{-2*pi}</param>
10+
<param name="max">{2*pi}</param>
11+
</command_interface>
12+
<command_interface name="velocity">
13+
<param name="min">-3.15</param>
14+
<param name="max">3.15</param>
15+
</command_interface>
16+
<state_interface name="position">
17+
<!-- initial position for the mock system and simulation -->
18+
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
19+
</state_interface>
20+
<state_interface name="velocity">
21+
<param name="initial_value">0.0</param>
22+
</state_interface>
23+
<state_interface name="effort">
24+
<param name="initial_value">0.0</param>
25+
</state_interface>
26+
</joint>
27+
<joint name="${tf_prefix}shoulder_lift_joint">
28+
<command_interface name="position">
29+
<param name="min">{-2*pi}</param>
30+
<param name="max">{2*pi}</param>
31+
</command_interface>
32+
<command_interface name="velocity">
33+
<param name="min">-3.15</param>
34+
<param name="max">3.15</param>
35+
</command_interface>
36+
<state_interface name="position">
37+
<!-- initial position for the mock system and simulation -->
38+
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
39+
</state_interface>
40+
<state_interface name="velocity">
41+
<param name="initial_value">0.0</param>
42+
</state_interface>
43+
<state_interface name="effort">
44+
<param name="initial_value">0.0</param>
45+
</state_interface>
46+
</joint>
47+
<joint name="${tf_prefix}elbow_joint">
48+
<command_interface name="position">
49+
<param name="min">{-pi}</param>
50+
<param name="max">{pi}</param>
51+
</command_interface>
52+
<command_interface name="velocity">
53+
<param name="min">-3.15</param>
54+
<param name="max">3.15</param>
55+
</command_interface>
56+
<state_interface name="position">
57+
<!-- initial position for the mock system and simulation -->
58+
<param name="initial_value">${initial_positions['elbow_joint']}</param>
59+
</state_interface>
60+
<state_interface name="velocity">
61+
<param name="initial_value">0.0</param>
62+
</state_interface>
63+
<state_interface name="effort">
64+
<param name="initial_value">0.0</param>
65+
</state_interface>
66+
</joint>
67+
<joint name="${tf_prefix}wrist_1_joint">
68+
<command_interface name="position">
69+
<param name="min">{-2*pi}</param>
70+
<param name="max">{2*pi}</param>
71+
</command_interface>
72+
<command_interface name="velocity">
73+
<param name="min">-3.2</param>
74+
<param name="max">3.2</param>
75+
</command_interface>
76+
<state_interface name="position">
77+
<!-- initial position for the mock system and simulation -->
78+
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
79+
</state_interface>
80+
<state_interface name="velocity">
81+
<param name="initial_value">0.0</param>
82+
</state_interface>
83+
<state_interface name="effort">
84+
<param name="initial_value">0.0</param>
85+
</state_interface>
86+
</joint>
87+
<joint name="${tf_prefix}wrist_2_joint">
88+
<command_interface name="position">
89+
<param name="min">{-2*pi}</param>
90+
<param name="max">{2*pi}</param>
91+
</command_interface>
92+
<command_interface name="velocity">
93+
<param name="min">-3.2</param>
94+
<param name="max">3.2</param>
95+
</command_interface>
96+
<state_interface name="position">
97+
<!-- initial position for the mock system and simulation -->
98+
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
99+
</state_interface>
100+
<state_interface name="velocity">
101+
<param name="initial_value">0.0</param>
102+
</state_interface>
103+
<state_interface name="effort">
104+
<param name="initial_value">0.0</param>
105+
</state_interface>
106+
</joint>
107+
<joint name="${tf_prefix}wrist_3_joint">
108+
<command_interface name="position">
109+
<param name="min">{-2*pi}</param>
110+
<param name="max">{2*pi}</param>
111+
</command_interface>
112+
<command_interface name="velocity">
113+
<param name="min">-3.2</param>
114+
<param name="max">3.2</param>
115+
</command_interface>
116+
<state_interface name="position">
117+
<!-- initial position for the mock system and simulation -->
118+
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>
119+
</state_interface>
120+
<state_interface name="velocity">
121+
<param name="initial_value">0.0</param>
122+
</state_interface>
123+
<state_interface name="effort">
124+
<param name="initial_value">0.0</param>
125+
</state_interface>
126+
</joint>
127+
</xacro:macro>
128+
</robot>

urdf/inc/ur_sensors.xacro

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
<xacro:macro name="ur_sensors" params="tf_prefix">
4+
<sensor name="${tf_prefix}tcp_fts_sensor">
5+
<state_interface name="force.x"/>
6+
<state_interface name="force.y"/>
7+
<state_interface name="force.z"/>
8+
<state_interface name="torque.x"/>
9+
<state_interface name="torque.y"/>
10+
<state_interface name="torque.z"/>
11+
</sensor>
12+
</xacro:macro>
13+
</robot>
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
4+
<xacro:include filename="$(find ur_description)/urdf/inc/ur_joint_control.xacro" />
5+
<xacro:include filename="$(find ur_description)/urdf/inc/ur_sensors.xacro" />
6+
7+
<xacro:macro name="ur_ros2_control" params="
8+
name
9+
tf_prefix
10+
mock_sensor_commands:=false
11+
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
12+
">
13+
14+
<ros2_control name="${name}" type="system">
15+
<hardware>
16+
<plugin>mock_components/GenericSystem</plugin>
17+
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
18+
<param name="state_following_offset">0.0</param>
19+
</hardware>
20+
<xacro:ur_joint_control_description
21+
tf_prefix="${tf_prefix}"
22+
initial_positions="${initial_positions}"
23+
/>
24+
25+
<xacro:ur_sensors
26+
tf_prefix="${tf_prefix}"
27+
/>
28+
</ros2_control>
29+
</xacro:macro>
30+
</robot>

0 commit comments

Comments
 (0)