Skip to main content

Visualizing the Robot (RViz)

A robot is made of joints connected by links. To enhance modularity, the kinematic and dynamic parameters are described in a Unified Robot Description Format (URDF) file, which primarily consists of two tags: <link> and <joint>.


What is a URDF File?

A <link> represents a rigid body in the robot and supports up to three subtags:

SubtagDescription
<visual>Defines the 3D mesh used for rendering in RViz.
<collision>Defines the simplified geometry used for collision detection.
<inertial>Specifies mass and inertia tensors for physics simulation.
note

The base link has no <inertial> tag because it is fixed and does not move.

Base link (no inertial):

<link name="manipulator_base_link">
<visual>
<origin xyz="0. 0. 0."/>
<geometry>
<mesh filename="package://ulixarm_description/meshes/visual/base_link.stl"/>
</geometry>
</visual>
<collision>
<origin xyz="0. 0. 0."/>
<geometry>
<mesh filename="package://ulixarm_description/meshes/collision/base_link.stl"/>
</geometry>
</collision>
</link>

Standard link (with inertial):

<link name="manipulator_link1">
<visual>
<origin xyz="0. 0. 0."/>
<geometry>
<mesh filename="package://ulixarm_description/meshes/visual/link_1.stl"/>
</geometry>
</visual>
<collision>
<origin xyz="0. 0. 0."/>
<geometry>
<mesh filename="package://ulixarm_description/meshes/collision/link_1.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0. 0. 0.037"/>
<mass value="0.480"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.002"/>
</inertial>
</link>

Joints

A <joint> connects two links — a parent and a child — and defines how they move relative to each other.

SubtagDescription
<origin>Position and orientation of the joint relative to the parent link.
<parent>The upstream link in the kinematic chain.
<child>The downstream link driven by this joint.
<axis>The axis of rotation or translation (unit vector).
<limit>Defines effort, velocity, and angular range constraints.
<joint name="joint1" type="revolute">
<origin rpy="0. 0. 0." xyz="0. 0. 0.0533"/>
<parent link="manipulator_base_link"/>
<child link="manipulator_link1"/>
<axis xyz="0 0 1"/>
<limit effort="27.0" lower="-1.570796326795" upper="1.570796326795" velocity="8.0"/>
</joint>
tip

You can explore the full URDF of the UlixArm in the ulixarm_description package.

note

You may notice .xacro files alongside the URDF — don't be alarmed. Xacro (XML Macros) is a preprocessor for URDF that allows you to use variables, math expressions, and macros to avoid repetition and keep descriptions clean. It compiles down to a standard URDF at runtime.

tip

For a step-by-step guide on writing your own URDF, refer to the official ROS 2 URDF tutorial.


Run the Demo

Clone the tutorial repository:

git clone https://github.com/itacarobotics/ulixarm_tutorial.git

Navigate into the repository:

cd ulixarm_tutorial

Build the packages:

colcon build

Source the environment:

source install/setup.bash
warning

You must source the environment in every new terminal. If you followed the Getting Started guide, the ROS environment is already sourced automatically via .bashrc.

Launch the demo:

ros2 launch exercise_1 display.launch.py

RViz will open displaying the robot model. Use the Joint State Publisher GUI to interactively change the angle of each joint.

info

Some joints will rotate clockwise and others counter-clockwise for a positive angle value. This is determined by the physical orientation of the motors in the mechanical assembly.