Skip to content
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
8 changes: 8 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -81,3 +81,11 @@ parameters file.
As mentioned above, see the `urdf/ur.urdf.xacro` file as an example to integrate a UR robot into
your scene description. Basically, you could create a copy of that file and extend it with the
modifications from your specific scene.

### Using description with ros2_control
The description itself does not contain a `ros2_control` tag. However, the package provides a couple
of helper files to create your own `ros2_control` tag describing the robot's joint control
mechanisms. See the [`urdf/ur_mocked.urdf.xacro`](urdf/ur_mocked.urdf.xacro)
file as an example using [mock
hardware](https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/mock_components_userdoc.html)
to control the robot.
11 changes: 7 additions & 4 deletions test/test_ur_urdf_xacro.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,20 +32,23 @@
import shutil
import subprocess
import tempfile
import pytest

from ament_index_python.packages import get_package_share_directory


def test_ur_urdf_xacro():
@pytest.mark.parametrize(
"ur_type", ["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"]
)
@pytest.mark.parametrize("description_file", ["ur.urdf.xacro", "ur_mocked.urdf.xacro"])
@pytest.mark.parametrize("prefix", ["", "my_ur_"])
def test_ur_urdf_xacro(ur_type, description_file, prefix):
# Initialize Arguments
ur_type = "ur3"
safety_limits = "true"
safety_pos_margin = "0.15"
safety_k_position = "20"
# General Arguments
description_package = "ur_description"
description_file = "ur.urdf.xacro"
prefix = '""'

joint_limit_params = os.path.join(
get_package_share_directory(description_package), "config", ur_type, "joint_limits.yaml"
Expand Down
128 changes: 128 additions & 0 deletions urdf/inc/ur_joint_control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="ur_joint_control_description" params="
tf_prefix
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)}
">
<joint name="${tf_prefix}shoulder_pan_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${tf_prefix}shoulder_lift_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${tf_prefix}elbow_joint">
<command_interface name="position">
<param name="min">{-pi}</param>
<param name="max">{pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['elbow_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${tf_prefix}wrist_1_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${tf_prefix}wrist_2_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
<joint name="${tf_prefix}wrist_3_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
</joint>
</xacro:macro>
</robot>
13 changes: 13 additions & 0 deletions urdf/inc/ur_sensors.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="ur_sensors" params="tf_prefix">
<sensor name="${tf_prefix}tcp_fts_sensor">
<state_interface name="force.x"/>
<state_interface name="force.y"/>
<state_interface name="force.z"/>
<state_interface name="torque.x"/>
<state_interface name="torque.y"/>
<state_interface name="torque.z"/>
</sensor>
</xacro:macro>
</robot>
30 changes: 30 additions & 0 deletions urdf/ros2_control_mock_hardware.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find ur_description)/urdf/inc/ur_joint_control.xacro" />
<xacro:include filename="$(find ur_description)/urdf/inc/ur_sensors.xacro" />

<xacro:macro name="ur_ros2_control" params="
name
tf_prefix
mock_sensor_commands:=false
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)}
">

<ros2_control name="${name}" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</hardware>
<xacro:ur_joint_control_description
tf_prefix="${tf_prefix}"
initial_positions="${initial_positions}"
/>

<xacro:ur_sensors
tf_prefix="${tf_prefix}"
/>
</ros2_control>
</xacro:macro>
</robot>
Loading