Skip to content

Commit

Permalink
Add mock components ros2_control example
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Nov 15, 2023
1 parent eeb824b commit 6497b9d
Show file tree
Hide file tree
Showing 3 changed files with 99 additions and 0 deletions.
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.
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>
61 changes: 61 additions & 0 deletions urdf/ur_mocked.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="$(arg name)">
<!-- robot name parameter -->
<xacro:arg name="name" default="ur"/>
<!-- import main macro -->
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
<xacro:include filename="$(find ur_description)/urdf/ros2_control_mock_hardware.xacro" />

<!-- possible 'ur_type' values: ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e, ur20 -->
<!-- the default value should raise an error in case this was called without defining the type -->
<xacro:arg name="ur_type" default="ur5x"/>

<!-- parameters -->
<xacro:arg name="tf_prefix" default="" />
<xacro:arg name="joint_limit_params" default="$(find ur_description)/config/$(arg ur_type)/joint_limits.yaml"/>
<xacro:arg name="kinematics_params" default="$(find ur_description)/config/$(arg ur_type)/default_kinematics.yaml"/>
<xacro:arg name="physical_params" default="$(find ur_description)/config/$(arg ur_type)/physical_parameters.yaml"/>
<xacro:arg name="visual_params" default="$(find ur_description)/config/$(arg ur_type)/visual_parameters.yaml"/>
<xacro:arg name="transmission_hw_interface" default=""/>
<xacro:arg name="safety_limits" default="false"/>
<xacro:arg name="safety_pos_margin" default="0.15"/>
<xacro:arg name="safety_k_position" default="20"/>
<xacro:arg name="mock_sensor_commands" default="false" />

<!--When using gazebo simulations absolute paths are necessary.-->
<xacro:arg name="force_abs_paths" default="false" />

<!-- initial position for simulations (Mock Hardware, Gazebo, Ignition) -->
<xacro:arg name="initial_positions_file" default="$(find ur_description)/config/initial_positions.yaml"/>

<!-- convert to property to use substitution in function -->
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

<!-- create link fixed to the "world" -->
<link name="world" />

<!-- arm -->
<xacro:ur_robot
name="$(arg name)"
tf_prefix="$(arg tf_prefix)"
parent="world"
joint_limits_parameters_file="$(arg joint_limit_params)"
kinematics_parameters_file="$(arg kinematics_params)"
physical_parameters_file="$(arg physical_params)"
visual_parameters_file="$(arg visual_params)"
safety_limits="$(arg safety_limits)"
safety_pos_margin="$(arg safety_pos_margin)"
safety_k_position="$(arg safety_k_position)"
force_abs_paths="$(arg force_abs_paths)"
>
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
</xacro:ur_robot>

<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="$(arg name)"
tf_prefix="$(arg tf_prefix)"
mock_sensor_commands="$(arg mock_sensor_commands)"
initial_positions="${xacro.load_yaml(initial_positions_file)}"
/>
</robot>

0 comments on commit 6497b9d

Please sign in to comment.