Extras
Despite all current customization options, we still would like our users to be able to add-in their existing custom URDF to the robot platform URDF and pass in and overwrite parameters to all platform nodes. Extras have the following entries:
- urdf:
- package: name of the ROS 2 package that contains the extras URDF (optional).
- path: relative path within the package or absolute path to robot extras URDF
- launch:
- package: name of the ROS 2 package that contains the extras launch file (optional).
- path: relative path within the package or absolute path to robot extras launch file
- ros_parameters: in YAML to pass in parameters to platform nodes. This is useful to change parameters such as the robot's velocity and acceleration.
extras:
urdf:
package: package_name
path: relative/path/to/urdf/in/package.urdf.xacro # or can contain /absolute/path/to/urdf.urdf.xacro
launch:
package: package_name
path: relative/path/to/launch/in/package.launch.py
ros_parameters: {} # node parameters, see below
Remember, absolute paths start with /
and relative paths do not.
If your extras file is in a ROS package built from source in a workspace, make sure to
add the workspace to robot.yaml
by adding it
to system.ros2.workspaces
.
URDF Extras
If an extras.urdf
is specified, it is included as part of the robot_description
. The specified
URDF file can either be an absolute path on the robot's filesystem or a relative path within a ROS
package:
Absolute path
platform:
extras:
urdf:
path: /home/robot/my_urdf_extras.urdf.xacro
Relative path within a ROS package
platform:
extras:
urdf:
package: my_robot_extras
path: urdf/my_urdf_extras.urdf.xacro
URDF Extras Example
This example assumes you are modifying robot.yaml
on a physical robot. The same process will
also work if you are using a simulation.
1. Create your URDF file
First, create a URDF file and save it on the robot. This example adds a simple cylindrical antenna:
<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<link name="my_antenna">
<visual>
<geometry>
<cylinder radius="0.01" length="0.4" />
</geometry>
<material name="grey">
<color rgba="0.6 0.6 0.6 1.0" />
</material>
<origin xyz="0.0 0.0 0.2" rpy="0.0 0.0 0.0" />
</visual>
<collision>
<geometry>
<cylinder radius="0.01" length="0.4" />
</geometry>
<origin xyz="0.0 0.0 0.2" rpy="0.0 0.0 0.0" />
</collision>
</link>
<joint name="my_antenna_joint" type="fixed">
<parent link="default_mount" />
<child link="my_antenna" />
<origin xyz="-0.2 0.1 0.0" rpy="0.0 0.0 0.0" />
</joint>
</robot>
Save this file as /home/robot/my_antenna.urdf.xacro
on the robot.
2. Modify robot.yaml
Add the following to robot.yaml
:
platform:
extras:
urdf:
path: /home/robot/my_antenna.urdf.xacro
The robot's URDF will now include the antenna, as shown in the image below:

my_antenna
custom URDFExtras Launch
If an extras.launch
is specified, it is launched as part of the clearpath-platform-extras.service
job. To check the status
of the extras launch, run
systemctl status clearpath-platform-extras.service
To view the raw output from the extras launch, run
sudo journalctl -fu clearpath-platform-extras.service
ROS Parameters
A common use case is to set and update the parameters to the platform_velocity_controller
node. These can be used to modify the linear and angular velocity and acceleratation.
These can be passed in as follows:
- A200
- J100
- W200
A200 Husky Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
wheel_radius: 0.1651
linear.x.max_velocity: 1.0
linear.x.min_velocity: -1.0
linear.x.max_acceleration: 3.0
linear.x.min_acceleration: -3.0
angular.z.max_velocity: 2.0
angular.z.min_velocity: -2.0
angular.z.max_acceleration: 6.0
angular.z.min_acceleration: -6.0
J100 Jackal Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
wheel_radius: 0.098
linear.x.max_velocity: 2.0
linear.x.min_velocity: -2.0
linear.x.max_acceleration: 20.0
linear.x.min_acceleration: -20.0
angular.z.max_velocity: 4.0
angular.z.min_velocity: -4.0
angular.z.max_acceleration: 25.0
angular.z.min_acceleration: -25.0
W200 Warthog Controller Defaults:
platform:
extras:
ros_parameters:
platform_velocity_controller:
wheel_radius: 0.3
linear.x.max_velocity: 5.0
linear.x.min_velocity: -5.0
linear.x.max_acceleration: 50.0
linear.x.min_acceleration: -50.0
angular.z.max_velocity: 4.0
angular.z.min_velocity: -4.0
angular.z.max_acceleration: 40.0
angular.z.min_acceleration: -40.0