2.1 Create a Mobile Robot with URDF and Visualize it
In this tutorial, we will create a mecanum mobile robot from scratch with URDF (Unified Robot Description Format), and then visualize the robot in RViz, a 3D visualization tool for ROS 2.

A Mecanum wheel is an omnidirectional wheel design to move in any direction, which is widely used in various robot products. It is far more fun and helpful to create a URDF file for a real-world robot you designed or you work with at your job or school.


The official tutorial for creating a URDF file is here on the ROS 2 website. The URDF file gives the robot a digital body that software can interact with, and it allows software tools to understand the robot’s structure, enabling tasks like simulation, motion planning, and sensor data interpretation etc.
Prerequisites
You have a Ubuntu 24.04 PC or VM with ROS2 Jazzy and Gazebo installed, if not, check our previous tutorials.
Installed urdf-tutorial package.
sudo apt-get install ros-${ROS_DISTRO}-urdf-tutorialYou can find the code here on GitHub.
If you want to save the code on Github, check our previous video on Youtube.
Create a Package
The first step is to create a ROS 2 package in your ros workspace. Open a new terminal window, and create a new folder named mec_mobile.
1. Create the package where we will store our URDF file.
The mec_mobile_description package contains the robot description files that define the physical aspects of a robot, including its geometry, kinematics, dynamics, and visual aspects.
2. Then, let’s create a metapackage for this project.
A metapackage doesn’t contain anything except a list of dependencies to other packages. You can use a metapackage to make it easier to install multiple related packages at once. Example.
Configure your package.xml file in VS Code or gedit:
3. Add a README.md to describe what the package is about.
I also recommend adding placeholder README.md files to the mec_mobile folder. The mec_mobile package is a metapackage. It contains lists of dependencies to other packages.
As well as the mec_mobile_description folder.
4. Now let’s build our new package:
Check our new package. Open a new terminal window or source the .bashrc first in current:
5. Create the following folders:
Add Meshe Files
Mesh files make your robot look realistic in robotics simulation and visualization programs. They visually represent the 3D shape of the robot parts, and are typically in formats such as STL (Stereo Lithography – .stl) or COLLADA (.dae).
The mesh files we use here were already available in this GitHub repository. However, if you want to create your own custom 3D printed robot from scratch, and make your own mesh files:
Design the robot’s 3D models using CAD programs like Onshape, Fusion 360, or Solidworks.
Export the 3D models as mesh files in formats like STL or COLLADA. These files contain information about the robot’s shape, including vertices, edges, and faces.
If needed, use a tool like Blender to simplify the mesh files. This makes them easier to use in simulations and visualizations.
Add the simplified mesh files to your URDF file to visually represent what the robot looks like.
Just pull these mesh files to corresponding directory of our package.
Configure CMakeLists.txt and package.xml
Let’s open Visual Studio Code and config the files for mec_mobile_description package.
Configure the CMakeLists.txt for the mec_mobile_description package:
Make sure your package.xml for the mec_mobile_description package as follows:
Build the Package
Before building the package, install dependencies:
You should see: All required rosdeps installed successfully. If not, type your password, and install the required dependencies.
Now open a terminal window, and run colcon build:
Create the URDF File
Now let’s create our URDF file. We will actually create it in XACRO format. XACRO files using macros and variables to simplify complex robot descriptions.
Before a ROS tool can use the XACRO file, it must be processed (translated) into a URDF file first, which allows for the dynamic generation of robot descriptions based on the XACRO file.
Open a terminal window, and type this command to create all the files we need:
Robot Base
Let’s start with creating our base: robot_3d_base.urdf.xacro
Robot Wheels
Then create a generic mecanum wheel: mecanum_wheel.urdf.xacro
RGBD Camera
Create the RGBD camera: rgbd_camera.urdf.xacro. An RGBD camera that captures colors (RGB) information and measures depth (the D stands for depth). it allows the camera to create 3D maps of its surroundings.
The main camera link holds the visual 3D model (loaded from an STL file) and can optionally include other physical properties like collision geometry for simulation.
What makes RGBD links sophisticated is its handling of multiple camera frames:
Depth frame: Captures distance information
Infrared frames (infra1 and infra2): Used for stereo depth perception
Color frame: Regular RGB camera
Optical frames: Aligned with standard ROS conventions
Each frame is connected by fixed joints with specific offsets.
You can find heaps of sensors that can be implemented in Gazebo simulator in this GitHub repository.
Robot LIDAR
Create the LIDAR: lidar.urdf.xacro
We will add the LIDAR plugin so we can generate simulated LIDAR data in a future tutorial.
Robot IMU
Now let’s create the IMU: imu.urdf.xacro
An IMU (Inertial Measurement Unit) is a sensor that measures movement, specifically acceleration, rotation, and sometimes magnetic fields, to help determine an object’s position and motion.
Full Robot
Finally, let’s create the full robot, bringing together all the components we have created:
URDF Explanation
Build the Package
Now let’s build the package.
Visualize the URDF in RViz
Let’s visualize the URDF files in RViz.
RViz (short for “ROS Visualization”) is a 3D visualization tool for robots that allows you to view the robot’s sensors, environment, and state. I use it all the time to visualize and debug my robots.
Now launch the URDF files. The conversion from XACRO to URDF happens behind the scenes. Be sure to have the correct path to your XACRO file.
By convention, the red axis is the x-axis, the green axis in the y-axis, and the blue axis is the z-axis. Uncheck the TF checkbox to turn off the axes.
You can use the Joint State Publisher GUI pop-up window to move the links around.

On the left panel under Displays, play around by checking and unchecking different options.
You can also see what simulation engines will use to detect collisions: Uncheck “Visual Enabled” under Robot Model and check “Collision Enabled.”
Under Robot Model, you can see how the mass distribution by unchecking “Visual Enabled” and “Collision Enabled” and checking the “Mass” checkbox under “Mass Properties”.
You can also see the coordinate frames. Open a new terminal window, and type the following commands:
To see the coordinate frames, type:
Last updated