Robot YAML
Our robots provide users with a wide range of customization options: sensors, sensor mounting structures, and custom-made parts. Matching the flexibility of our hardware, Clearpath's ROS 2 system is designed to keep all these customization decisions in a single configuration file.
The Clearpath Robot Configuration YAML, or robot.yaml
for short, contains all information pertinent to the entire robot system, allowing robot builders and users to quickly and easily modify any ROS 2 component.
Overview
The robot.yaml
is composed of five major sections:
- system level information such as the robot's hostname, IP, and ROS middleware implementation.
- platform level configurations such as robot specific mounting structures and specifying an extra URDF to attach.
- links that are URDF primitives: boxes, cylinders, and meshes.
- mounts that are predefined, generic, sensor mounting structures.
- sensors that are selected from an inventory of Clearpath supported sensors.
Additionally, there are two other, required parameters:
- The robot's serial_number; which is used to determine the model and version.
- The configuration version to use, as future updates are released.
Sample

Below is the sample Husky A200 robot YAML of the robot displayed above. In the following sections, we will reference each and every component of this sample file, and show how to robot looks as we build it up.
Find more samples robot.yaml
configuration files in the Clearpath Configuration repository.
You can also skip to each section to get an explanation of each part of the sample configuration:
Sample A200 YAML
serial_number: a200-0000
version: 0
system:
hosts:
self: cpr-a200-0000
platform:
cpr-a200-0000: 192.168.131.1
onboard: {}
remote: {}
ros2:
username: administrator
namespace: a200_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces: []
platform:
controller: ps4
attachments:
front_bumper:
enabled: true
model: default
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
rear_bumper:
enabled: true
model: default
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
structure:
enabled: true
model: sensor_arch_300
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
top_plate:
enabled: true
model: pacs
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extras:
urdf: null
links:
box:
- name: user_bay_cover
parent: top_plate_link
xyz: [0.0, 0.0, 0.00735]
rpy: [0.0, 0.0, 0.0]
size: [0.4, 0.4, 0.002]
cylinder: []
frame: []
mesh: []
sphere: []
mounts:
bracket:
- parent: top_plate_mount_d1
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
model: horizontal
fath_pivot:
- parent: sensor_arch_mount
xyz: [0.0, 0.0, -0.021]
rpy: [3.1415, 0.0, 0.0]
angle: 0.0
riser: []
sick: []
post: []
disk: []
sensors:
camera:
- model: intel_realsense
urdf_enabled: true
launch_enabled: true
parent: fath_pivot_0_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
camera:
camera_name: camera_0
device_type: d435
serial_no: '0'
enable_color: true
rgb_camera.profile: 640,480,30
enable_depth: true
depth_module.profile: 640,480,30
pointcloud.enable: true
gps: []
imu: []
lidar2d:
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: bracket_0_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -2.356
angle_max: 2.356
lidar3d:
- model: velodyne_lidar
urdf_enabled: true
launch_enabled: true
parent: sensor_arch_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
Serial Number
The Clearpath serial number is composed of two sections: an alpha-numerical code corresponding to the robot platform, followed by an integer corresponding to the unit number, and separated by a hyphen, -
. e.g. a200-0001
.
At this moment, the supported robot platforms are:
- Husky A200:
a200-0000
- Jackal J100:
j100-0000
Every robot platform has specific attachments, i.e. platform specific parts, that are selected based on the serial number passed. Therefore, it is required that a serial number is specified in the robot.yaml
.
Sample
In our sample, we use a Husky A200 and therefore have set our serial number to:
serial_number: "a200-0000"
System
Proper networking setup is crucial in setting up the ROS 2 middleware and ensure other onboard computers communicate reliably.
Hosts
The hosts section serves as a way to match IP addresses to hostnames. By default, Clearpath robots use the serial number as the hostname and have a default IP of 192.168.131.1
.
- The self entry refers to what hostname is this configuration file on.
- The platform entry refers to the hostname and IP of the robot platform's main computer.
- The onboard entry is used to define the hostname and IP of other computers on the robot.
- The remote entry is used to define the hostname and IP of computers in the system that are not on the robot, such as a user's PC.
ROS 2 Environment
The ros2 sections is necessary to setup the ROS 2 middleware.
- username must match the username of the user that is to run all ROS nodes.
- namespace specified will be appended as a prefix to all sensor topics to prevent topic cloberring when multiple robots are on the same network and domain ID.
- domain_id specifies the ROS 2 domain ID to use.
- rmw_implementation specifies the ROS 2 middleware to use. Currently, it only supports
rmw_fastrtps_cpp
. - workspaces indicates a list of workspaces that need to be sourced by specifying the path to the setup.py
Sample
Sample A200 System Section
In our sample, we have a Husky A200 platform whose primary computer has hostname: cpr-a200-0000
and IP: 192.168.131.1
.
And, note that this configuration YAML is meant to be on that primary computer, hence self: cpr-a200-0000
.
By default, all Clearpath robots use username administrator
and the robot's namespace matches the serial_number
.
system:
hosts:
self: cpr-a200-0000
platform:
cpr-a200-0000: 192.168.131.1
onboard: {}
remote: {}
ros2:
username: administrator
namespace: a200_0000
domain_id: 0
rmw_implementation: rmw_fastrtps_cpp
workspaces: []
At this point, with just the serial_number and system defined: our robot is just the standard Husky A200 platform, and looks like this:

Platform
Every robot platform has unique structures such as versatile sensor mounting solutions, wireless charging receivers, and waterproofing enclosures; we refer to these as attachments.
Joystick Controller
We support two types of controllers:
- ps4: standard Playstation4 controller.
- logitech: Logitech F710
controller: ps4 # or logitech
Attachments
There are four types of attachments:
- bumpers modify the front face and rear face of the robot platform.
- fenders modify the area above the wheels on the front and rear of the platform.
- top_plates modify the top face of the robot platform.
- structures are large custom parts that are added atop the top plate.
Husky A200
The Husky A200 has a few models for each of it's attachments:
- bumpers:
- default: standard bumpers.
- wibotic: wireless charging receiver.
front_bumper:
enabled: true
model: default # or wibotic
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
rear_bumper:
enabled: true
model: default # or wibotic
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
- top plate:
- default: standard Husky A200 top plate.
- large: extended top plate, used to allow for enough space to mount large payloads.
- pacs: comes with 80x80 mm mounting screw holes for versatile sensor placement.
top_plate:
enabled: true
model: default # or 'pacs' or 'large'
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
- struture:
- sensor_arch_300: 300mm tall extrusion sensor arch.
- sensor_arch_510: 510mm tall extrusion sensor arch.
structure:
enabled: false
model: sensor_arch_300 # or sensor_arch_510
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
Jackal J100
The Jackal J100 currently only has customization options with it's fenders.
- fenders can be swapped from the
default
model to thesensor
model that has a mounting location for a small lidar or camera.
front_fender:
enabled: true # or false
model: default # or sensor
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
rear_fender:
enabled: true # or false
model: default # or sensor
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
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: absolute path to URDF to add to robot platform URDF.
- 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: null # /absolute/path/to/urdf
ros_parameters: {} # node parameter
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 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
Sample
Sample A200 Platform Section

In this sample, we swapped the top plate from the default model to the pacs model. Notice all the links added by the pacs plate below, compared to the default plate above.
top_plate:
enabled: true
model: pacs # switched from 'default' to 'pacs'
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]

Then, we added a sensor arch to add our sample sensors to. We can do this by simply enabling the structure and setting the model to sensor_arch_300.
structure:
enabled: true
model: sensor_arch_300
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]

In terms of the front_bumper and rear_bumper, we left these as defaults. And, since we are not including any customization URDF or launch parameters; the resulting platform section look like this:
platform:
controller: ps4
attachments:
front_bumper:
enabled: true
model: default
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
rear_bumper:
enabled: true
model: default
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extension: 0.0
structure:
enabled: true
model: sensor_arch_300
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
top_plate:
enabled: true
model: pacs
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
extras:
urdf: null
ros_parameters: {}
Links
Links are any URDF primitive:
- frame in the URDF without any geometry, i.e. just a frame.
frame:
- name: link_name
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
- box of given length, width, and height.
box:
- name: box_name
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
size: [0.01, 0.01, 0.01]
- cylinder of given radius and height.
cylinder:
- name: cylinder_name
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
radius: 0.01
length: 0.01
- sphere of given radius.
sphere:
- name: sphere_name
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
radius: 0.01
- mesh from a given absolute path to STL or OBJ file.
mesh:
- name: mesh_name
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
visual: /absolute/path/to/mesh.stl
If a user needs to add a mesh or primitive to represent a payload on their robot, they can either create a URDF and use the platform extras, or they can add an link directly through the robot.yaml
.
Just as is the case in URDF, links are added at the center of the primitive. In other words, you will need to slide up all links by half their height to have it "sit" on its parent link.
Sample
Sample A200 Links Section

In this sample, we will use links to add thin box to cover up the user bay.
We add an entry under the box list:
box:
- name: user_bay_cover
parent: top_plate_link # add it to the top_plate_link
xyz: [0.0, 0.0, 0.00735] # move it up 6.35mm (thickness of top plate) and move it up 1mm (half height of the box)
rpy: [0.0, 0.0, 0.0]
size: [0.4, 0.4, 0.002] # length 400mm, width 400mm and 2mm thick.

We leave the rest of the lists all empty, for the resulting links section:
links:
box:
- name: user_bay_cover
parent: top_plate_link
xyz: [0.0, 0.0, 0.00735]
rpy: [0.0, 0.0, 0.0]
size: [0.4, 0.4, 0.002]
cylinder: []
frame: []
mesh: []
sphere: []
Mounts
Most sensors can use similar mounting structures. Therefore, we want to keep mounts separate from sensors, such that users could attach their own sensors to existing mounts.
The following mounts are available:
- riser: a plate with the defined number of rows and columns of an 80mm x 80mm grid.
riser:
- parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
rows: 4 # rows of 80mm x 80mm grid
columns: 4 # columns of 80mm x 80mm grid
thickness: 0.00635
- bracket: a small 100mm x 100mm plate with 80mm x 80mm screw holes to attach it to the grid. It comes with hole patterns to attach all supported small sensors.
bracket:
- parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
model: horizontal # or large or vertical
- fath_pivot: generally a camera mount on a single axis that can be adjusted to change the pitch of the camera.
fath_pivot:
- parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
angle: 0.0 # in radian
- sick: are mounts specifically designed to mount SICK LiDARs. The orientation of the LiDAR on the mount can be set to either
upright
orinverted
.
sick:
- parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
model: inverted # or upright
- post: are vertical extrusion rails to which sensors can be added.
post:
- parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
model: single # or dual or quad
spacing: 0.08 # distance between multiple posts if model is dual or quad
height: 0.075 # height of post
- disk: are circular plates which are used to mount circular sensors, i.e. the Velodyne
disk:
- parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
Sample
Sample A200 Mounts Section

In this sample, we will add a bracket to mount a LiDAR to the front of the Husky A200.
We select the top_plate_mount_d1, i.e. the middle (d), front (1), 80mm x 80mm mounting location on the pacs top plate.
bracket:
- parent: top_plate_mount_d1
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
model: horizontal

Then, we want to add a camera to the sensor arch. However, we will complicate things by adding it upside down to the extrusion.
We choose a fath_pivot mount, and then we set its parent to the sensor_arch_mount.
Using the xyz entry, we lower the mount by 21mm to get it under the sensor arch; then, we roll it by PI to get it upside down.
fath_pivot:
- parent: sensor_arch_mount # mount atop the sensor arch
xyz: [0.0, 0.0, -0.021] # lower pivot mount to below the sensor arch
rpy: [3.1415, 0.0, 0.0] # roll pivot mount to flip it upside down
angle: 0.0

Since we did not need a riser, we leave that section empty; the resulting mounts section:
mounts:
bracket:
- parent: top_plate_mount_d1
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
model: horizontal
fath_pivot:
- parent: sensor_arch_mount
xyz: [0.0, 0.0, -0.021]
rpy: [3.1415, 0.0, 0.0]
angle: 0.0
riser: []
sick: []
post: []
disk: []
Sensors
At Clearpath, we have been migrating our large inventory of tested sensor drivers from ROS 1 to ROS 2.
Sensors are split up into sections:
- Cameras: publish sensor_msgs/Image messages
- GPS: publish sensor_msgs/NavSatFix messages
- IMU: publish sensor_msgs/Imu messages
- LiDAR 2D: publish sensor_msgs/LaserScan messages
- LiDAR 3D: publish sensor_msgs/PointCloud2 messages
In ROS 2, sensors use a ros_parameters
YAML that contains all launch parameters for the driver node. To facilitate complete customization of these node parameters, the ros_parameters
section, under every sensor entry, serves as a way to pass those key-value pairs to the corresponding node.
By default, we pass tested parameters that are used on Clearpath robots.
Cameras
- intel_realsense:
camera:
- model: intel_realsense
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
camera:
camera_name: camera_0
device_type: d435
serial_no: "0"
enable_color: true
rgb_camera.profile: 640,480,30
enable_depth: true
depth_module.profile: 640,480,30
pointcloud.enable: true
- flir_blackfly:
camera:
- model: flir_blackfly
urdf_enabled: true
launch_enabled: true
parent: fath_pivot_0_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
flir_blackfly:
serial_number: 0
GPS
- swift_nav:
gps:
- model: swiftnav_duro
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
duro_node:
gps_receiver_frame_id: gps_0_link
ip_address: 192.168.131.30
ip_port: 55555
imu_frame_id: gps_0_link
- garmin_18x
gps:
- model: garmin_18x
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
nmea_navsat_driver:
frame_id: gps_0_link
port: /dev/ttyACM0
baud: 115200
- novatel_smart6
gps:
- model: novatel_smart6
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
nmea_navsat_driver:
frame_id: gps_0_link
port: /dev/ttyACM0
baud: 115200
- novatel_smart7
gps:
- model: novatel_smart7
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
nmea_navsat_driver:
frame_id: gps_0_link
port: /dev/ttyACM0
baud: 115200
IMU
- microstrain:
imu:
- model: microstrain_imu
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
microstrain_inertial_driver:
imu_frame_id: imu_0_link
port: /dev/microstrain_main
use_enu_frame: true
- chrobotics_um6:
imu:
- model: chrobotics_um6
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
um6_driver:
port: /dev/clearpath/imu
frame_id: imu_0_link
tf_ned_to_enu: true
- redshift_um7:
imu:
- model: redshift_um7
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
um7_driver:
port: /dev/clearpath/imu
frame_id: imu_0_link
tf_ned_to_enu: true
LiDAR 2D
- hokuyo_ust:
lidar2d:
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -2.356
angle_max: 2.356
- sick_lms1xx:
lidar2d:
- model: sick_lms1xx
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
lms1xx:
frame_id: lidar2d_0_laser
host: 192.168.131.20
port: 2111
LiDAR 3D
- velodyne_lidar - 16:
lidar3d:
- model: velodyne_lidar
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
- velodyne_lidar - 32C:
- model: velodyne_lidar
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: 32C
velodyne_transform_node:
model: 32C
calibration: /opt/ros/humble/share/velodyne_pointcloud/params/VeloView-VLP-32C.yaml
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser
Sample
Sample A200 Sensors Section

In this sample, we first add the velodyne_lidar
to the sensor_arch_mount
by simply changing the parent link.
lidar3d:
- model: velodyne_lidar
urdf_enabled: true
launch_enabled: true
parent: sensor_arch_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser

Next, we will add a hokuyo_ust
to the bracket we added earlier. Since that is the first bracket, then it's mounting location will be: bracket_0_mount
; setting the parent link of the sensor, we get:
lidar2d:
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: bracket_0_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -2.356
angle_max: 2.356

For the final step, we will add an intel_realsense
to the fath_pivot mount that we added. Because it is the first fath_pivot, it's mounting location will be: fath_pivot_0_mount
; setting the parent link of the sensor:
camera:
- model: intel_realsense
urdf_enabled: true
launch_enabled: true
parent: fath_pivot_0_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
camera:
camera_name: camera_0
device_type: d435
serial_no: '0'
enable_color: true
rgb_camera.profile: 640,480,30
enable_depth: true
depth_module.profile: 640,480,30
pointcloud.enable: true

Leaving the other sections empty, leaves us with the full sensors section:
sensors:
camera:
- model: intel_realsense
urdf_enabled: true
launch_enabled: true
parent: fath_pivot_0_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
camera:
camera_name: camera_0
device_type: d435
serial_no: '0'
enable_color: true
rgb_camera.profile: 640,480,30
enable_depth: true
depth_module.profile: 640,480,30
pointcloud.enable: true
gps: []
imu: []
lidar2d:
- model: hokuyo_ust
urdf_enabled: true
launch_enabled: true
parent: bracket_0_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
urg_node:
laser_frame_id: lidar2d_0_laser
ip_address: 192.168.131.20
ip_port: 10940
angle_min: -2.356
angle_max: 2.356
lidar3d:
- model: velodyne_lidar
urdf_enabled: true
launch_enabled: true
parent: sensor_arch_mount
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
velodyne_driver_node:
frame_id: lidar3d_0_laser
device_ip: 192.168.131.25
port: 2368
model: VLP16
velodyne_transform_node:
model: VLP16
fixed_frame: lidar3d_0_laser
target_frame: lidar3d_0_laser