How to Simulate a Robotic Arm in Gazebo – ROS 2 Jazzy

In this tutorial, we will simulate and control a robotic arm in Gazebo.  I will show you how to set up and control a robotic arm using ROS 2 Control and Gazebo

By the end of this tutorial, you will be able to build this:

arm-gripper-loop-mycobot-small

Prerequisites

All my code for this project is located here on GitHub.

What is Gazebo?

Ever wondered how robotics engineers test their robots without risking expensive hardware?

Enter Gazebo – a simulator that lets you test robots in a virtual world before building them in real life. You can work with different types of robots and connect them with ROS 2, which means your virtual tests will translate to real robots. This makes Gazebo an important tool when you’re developing and perfecting robotics projects.

What is ROS 2 Control?

Imagine you want to control a robot – maybe move its arm or make its wheels turn. You need a way for your computer programs to talk to the robot’s physical parts (like motors and sensors). This is where ROS 2 Control comes in.

ROS 2 Control is like a universal translator between:

  • Your control programs (the software you write)
  • The robot’s physical parts (the hardware)

How It Works

ros2_control_overview
  1. Where it runs:
    • ROS 2 Control lives on the main computer that controls your robot
    • This could be a laptop, Raspberry Pi, Intel NUC, or any computer running ROS 2
  2. Sending Commands (Software → Hardware)
    • You write a program to make the robot move
    • ROS 2 Control takes these commands
    • It translates them into instructions the robot’s hardware can understand
    • These instructions go to devices like Arduino boards that directly control the motors
  3. Getting Feedback (Hardware → Software)
    • The robot’s sensors and motors send back information
    • For example: “Motor #1 is currently at 45 degrees”
    • ROS 2 Control receives this information
    • It shares this data with other ROS 2 programs that need it

Real-World Example: Moving a Robotic Arm

ros2-control-mobile-manipulator-control-arch-independent_hardware

Let’s look at how ROS 2 Control works with a robotic arm that has 6 degrees of freedom (like the myCobot robotic arms) – meaning it can move in 6 different ways, just like your human arm. Each degree comes from a motor, or “joint,” that enables specific movements. Want to pick up a cup? Here’s how ROS 2 Control makes this happen:

  1. Your Program’s Command
    • You want the arm to move to pick up the cup.
    • Your program (i.e. MoveIt 2) calculates all the positions each joint needs to move through to get the gripper from the starting location to the goal location around the cup.
    • Your program sends a “joint trajectory” – think of it as a list of positions for each joint- to the Joint Trajectory Controller (which is part of ROS 2 Control)
    • For example: “Joint 1 should move from 0° to 45°, Joint 2 from 30° to 60°, etc…”
  2. ROS 2 Control’s Job
    • The Joint Trajectory Controller gets this list of joint positions
    • The Joint Trajectory Controller knows it needs to smoothly move through these positions and passes the appropriate angle values to the Hardware Interface.
    • The Hardware Interface converts these angles into commands the Arduino (or some other microcontroller) can understand
    • The Hardware Interface sends these commands to the microcontroller many times per second
  3. Arduino’s Role
    • Gets these commands through a USB cable
    • Controls the actual motors in the robot arm
    • Tells each motor exactly how fast and how far to turn
    • Also reads sensors (called encoders) on each motor
  4. Feedback Path (This is important!)
    • Arduino constantly reads the sensors: “Joint 1 is at 22°, Joint 2 is at 45°…”
    • Sends this information back to ROS 2 Control
    • ROS 2 Control shares this with your program
    • Your program can check if the arm is moving correctly
  5. Continuous Process
    • This whole cycle happens many times every second
    • Your program keeps checking the arm’s position
    • ROS 2 Control keeps sending updated commands
    • Arduino keeps moving motors and reading sensors
    • Until the arm reaches all the positions needed to pick up the cup

What ROS 2 Control Does For You

ROS 2 Control provides a standard hardware interface – think of it like a universal adapter between your software and robot hardware. With ROS 2 Control:

  • You only need to think about where you want the arm to move
  • Don’t need to worry about how to control individual motors
  • Can focus on the task (picking up the cup) instead of the details
  • Works with different types of robot arms – just change the settings
  • Write your robot program once
  • Want to switch from servo motors to stepper motors? Just update a configuration file
  • Change from Arduino to a different microcontroller? Just update the hardware interface
  • Your original program keeps working without changes
  • Can more easily share your code with others

A complete block diagram showing an overview of ROS 2 Control is on this page.

Real Hardware + ROS 2 Control: Following a Single Command

Let’s take a look at a more technical example of how ROS 2 Control works for a real robotics project. We will follow a joint position command as it travels through each part of ROS 2 Control, looking at exactly at the inputs and outputs at each stage. Think of it like tracking a package through the delivery system.

1. The Starting Point: Terminal Command or MoveIt 2 Action

INPUT: Your terminal command or Move It 2 action

ros2 topic pub /arm_controller/joint_trajectory trajectory_msgs/msg/JointTrajectory

OUTPUT: A ROS 2 message containing:

  • Joint names: [link1_to_link2, link2_to_link3, …, link6_to_link6flange]
  • Desired positions: [0.5, 0.2, 0.3, 0.1, 0.7, 0.0] (in radians)

2. ROS 2 Control Joint Trajectory Controller (The Message Processor)

INPUT: Exactly what we sent above

  • The joint names and positions from our message

OUTPUT: Command interface angle values (processed 100 times per second)

  • link1_to_link2/position: 0.5 radians
  • link2_to_link3/position: 0.2 radians
  • (and so on for each joint)

3. ROS 2 Control Hardware Interface (The Translator)

INPUT: Those command interface angle values

  • Position commands for each joint in radians

OUTPUT: A serial message to Arduino

  • e.g. “p <joint1_pos> <joint2_pos> <joint3_pos> …\r”
  • “p 1500 1200 1800 … \r”
  • Here, each value represents the target position of a servo in microseconds, corresponding to each joint in the arm.

4. Arduino (The Final Handler)

INPUT: The serial message from the ROS 2 Control hardware interface

OUTPUT: Motor commands

  • Servo1: 50.0 degrees
  • Servo2: 20.0 degrees
  • (and so on for each servo)

Gazebo + ROS 2 Control: Following a Single Command

Now that we have taken a look at what happens in a real robotics project, let’s understand how Gazebo and ROS 2 Control interact with each other by tracking the same joint command. 

1. The Starting Point: Terminal Command or MoveIt 2 Action

INPUT: Your terminal command or Move It 2 action

ros2 topic pub /arm_controller/joint_trajectory trajectory_msgs/msg/JointTrajectory

OUTPUT: A ROS 2 message containing:

  • Joint names: [link1_to_link2, link2_to_link3, …, link6_to_link6flange]
  • Desired positions: [0.5, 0.2, 0.3, 0.1, 0.7, 0.0] (in radians)

2. ROS 2 Control Joint Trajectory Controller (The Message Processor)

INPUT: Exactly what we sent above

  • The joint names and positions from our message

OUTPUT: Command interface angle values (processed 100 times per second)

  • link1_to_link2/position: 0.5 radians
  • link2_to_link3/position: 0.2 radians
  • (and so on for each joint)

3. GazeboSimSystem (The Virtual Hardware Interface)

INPUT: Those command interface values

  • Position commands for each joint in radians

OUTPUT: Gazebo physics commands (internal to Gazebo)

  • SetPosition(“link1_to_link2”, 0.5)
  • SetPosition(“link2_to_link3”, 0.2)
  • (and so on for each joint)

4. Gazebo Physics Engine (The Virtual Robot)

INPUT: Physics commands for each joint

  • Position setpoints in radians

OUTPUT: Simulated motion

  • Updates joint positions in physics simulation
  • Considers inertia, gravity, joint limits
  • Provides visual feedback in Gazebo

Key Similarities Between Gazebo and Real Hardware

  • Control Flow: Both use the same ROS 2 Control architecture and message pipeline
  • Joint Interfaces: Same position/velocity/effort command and state interfaces are used
  • Update Rate: Both typically run control loops at similar frequencies (e.g., 50Hz, 100Hz)
  • Command Format: Joint commands from the software (e.g. MoveIt 2) use identical message types and coordinate systems

Key Differences Between Gazebo and Real Hardware

  • Communication Layer: Real hardware requires serial protocols and motor drivers, while Gazebo interfaces directly through its simulation system
  • Motion Physics: Real robots must handle physical wear, friction and imperfections. Gazebo uses idealized physics models
  • System Feedback: Real hardware relies on potentially noisy sensor data, while Gazebo provides perfect state information from its physics engine
  • Error Handling: Real systems need robust error detection and recovery. Gazebo simulation can ignore many real-world failure modes

The beauty of simulation is that the commands flow through almost the same path, but instead of dealing with real motors and encoders, everything happens in the physics engine. This makes testing and development safer and faster.

Each stage transforms the command into something the next stage can understand, like a series of translators working together to deliver your message to the robot.

Let’s put this knowledge into practice by setting up our own robot simulation. We’ll start by creating the necessary ROS 2 packages that will house our configuration files, launch scripts, and test code.

Create Packages

Navigate to your workspace and create the following packages. You can replace the maintainer-name and maintainer email with your own information.

cd ~/ros2_ws/src/mycobot_ros2/
ros2 pkg create --build-type ament_cmake \
                --license BSD-3-Clause \
                --maintainer-name ubuntu \
                --maintainer-email automaticaddison@todo.com \
                mycobot_bringup
ros2 pkg create --build-type ament_cmake \
                --license BSD-3-Clause \
                --maintainer-name ubuntu \
                --maintainer-email automaticaddison@todo.com \
                mycobot_gazebo
ros2 pkg create --build-type ament_cmake \
                --license BSD-3-Clause \
                --maintainer-name ubuntu \
                --maintainer-email automaticaddison@todo.com \
                mycobot_moveit_config
ros2 pkg create --build-type ament_cmake \
                --license BSD-3-Clause \
                --maintainer-name ubuntu \
                --maintainer-email automaticaddison@todo.com \
                mycobot_system_tests

Update the package.xml files for all packages, including the metapackage. Be sure to add a good description line for each.

You can also update the metapackage with the new packages you just created.

cd mycobot_ros2
gedit package.xml
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>mycobot_ros2</name>
  <version>0.0.0</version>
  <description>myCobot series robots by Elephant Robotics (metapackage).</description>
  <maintainer email="automaticaddison@todo.todo">ubuntu</maintainer>
  <license>BSD-3-Clause</license>
  <buildtool_depend>ament_cmake</buildtool_depend>

  <exec_depend>mycobot_bringup</exec_depend>
  <exec_depend>mycobot_description</exec_depend>
  <exec_depend>mycobot_gazebo</exec_depend>
  <exec_depend>mycobot_moveit_config</exec_depend>
  <exec_depend>mycobot_system_tests</exec_depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

Edit package.xml

Now let’s make sure some key packages are installed to handle the integration between ROS 2 and Gazebo. One important package is ros_gz. Here is the GitHub repository, and here are the official installation instructions. Let’s walk through this together.

Open a terminal window, and go to your package.xml folder inside the mycobot_gazebo package.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_gazebo

Open the package.xml file.

Make sure it has this block:

<depend>controller_manager</depend>
<depend>gripper_controllers</depend>
<depend>gz_ros2_control</depend>
<depend>python3-numpy</depend>
<depend>rclcpp</depend>
<depend>ros_gz</depend>
<depend>ros_gz_bridge</depend>
<depend>ros_gz_image</depend>
<depend>ros_gz_sim</depend>
<depend>ros2_control</depend>
<depend>ros2_controllers</depend>
<depend>trajectory_msgs</depend>
<depend>xacro</depend>
<exec_depend>gz_ros2_control_demos</exec_depend>

controller_manager: Acts like a supervisor for all your robot’s ROS 2 controllers, making sure they work together properly.

gripper_controllers: Ready-to-use controllers that help you open and close robot grippers.

gz_ros2_control: The bridge that lets your simulated robot in Gazebo understand ROS 2 Control commands.

gz_ros2_control_demos: Example robot projects that show you how to use Gazebo with ROS 2 Control.

python3-numpy: A Python package that helps with math calculations for robotics.

rclcpp: The basic tools you need to write ROS 2 programs in C++.

ros_gz: Connects ROS 2 with the latest version of Gazebo so they can work together.

ros_gz_bridge: Helps ROS 2 and Gazebo talk to each other by translating their messages.

ros_gz_image: Handles camera images between ROS 2 and Gazebo simulation.

ros_gz_sim: The main package that lets you run robot simulations in Gazebo.

ros2_control: The main system that lets you control robots (both real and simulated) in ROS 2.

ros2_controllers: A collection of pre-made controllers for common robot movements.

trajectory_msgs: Messages that tell the robot how to move from point A to point B.

xacro: A tool that makes it easier to write and edit robot description files.

Edit CMakeLists.txt

Now open the CMakeLists.txt file, and add this block:

find_package(ament_cmake REQUIRED)
find_package(controller_manager REQUIRED)
find_package(gripper_controllers REQUIRED)
find_package(gz_ros2_control REQUIRED)
find_package(rclcpp REQUIRED)
find_package(ros_gz REQUIRED)
find_package(ros_gz_bridge REQUIRED)
find_package(ros_gz_image REQUIRED)
find_package(ros_gz_sim REQUIRED)
find_package(ros2_control REQUIRED)
find_package(ros2_controllers REQUIRED)
find_package(trajectory_msgs REQUIRED)
find_package(xacro REQUIRED)

Build the Workspace

Now let’s build our workspace.

cd ~/ros2_ws/
rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y
colcon build && source ~/.bashrc

Open a terminal window, and type:

echo "alias build='cd ~/dev_ws/ && colcon build && source ~/.bashrc'" >> ~/.bashrc

Now going forward, any time you want to build you workspace, just type:

build

Test Your Installation

Let’s test our installation:

ros2 pkg list | grep gz_ros2_control

You should see:

gz_ros2_control
gz_ros2_control_demos

Run an example:

ros2 launch ros_gz_sim gz_sim.launch.py gz_args:="shapes.sdf"

Here is what you should see:

1-shapes-sdf

Feel free to run the other demos which you can find here on the ros_gz GitHub or here on the gz_ros2_control GitHub.

ros2 launch ros_gz_sim_demos joint_states.launch.py 
2-joint-states-launch-py-gazebo

When you run each demo, you can explore the topics by typing:

ros2 topic list

To run the gripper example, type:

ros2 launch gz_ros2_control_demos gripper_mimic_joint_example_effort.launch.py
3-gripper-example

To close the gripper, type:

ros2 run gz_ros2_control_demos example_gripper

You can try the differential drive mobile robot example as well:

ros2 launch gz_ros2_control_demos diff_drive_example.launch.py
4-diff-drive-mobile-robot-gazebo

To move the robot from the terminal window, you can type:

ros2 topic pub /diff_drive_base_controller/cmd_vel geometry_msgs/msg/TwistStamped "{header: {stamp: now, frame_id: 'base_link'}, twist: {linear: {x: 0.2, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.5}}}" --rate 5

To stop the robot:

ros2 topic pub /diff_drive_base_controller/cmd_vel geometry_msgs/msg/TwistStamped "{header: {stamp: now, frame_id: 'base_link'}, twist: {linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}}" --rate 5

To move the robot using a program, type this command in another terminal window:

ros2 run gz_ros2_control_demos example_diff_drive

Create World Files

Now we will create an environment for our simulated robot.

Open a terminal window, and type:

cd ~/ros2_ws/src/mycobot_ros2/mycobot_gazebo/

Create a worlds folder and other folders we will need later:

mkdir -p worlds launch models

Now let’s create our world. The first world we will create is an empty world.

cd worlds
gedit empty.world

Add this code.

<?xml version="1.0" ?>

<sdf version="1.6">
  <world name="default">

    <!-- Plugin for simulating physics -->
    <plugin
      filename="gz-sim-physics-system"
      name="gz::sim::systems::Physics">
      <engine>
        <filename>libgz-physics-bullet-featherstone-plugin.so</filename>
      </engine>
    </plugin>

    <!-- Plugin for handling user commands -->
    <plugin
      filename="gz-sim-user-commands-system"
      name="gz::sim::systems::UserCommands">
    </plugin>

    <!-- Plugin for broadcasting scene updates -->
    <plugin
      filename="gz-sim-scene-broadcaster-system"
      name="gz::sim::systems::SceneBroadcaster">
    </plugin>

    <!-- Plugin for handling sensors like the LIDAR -->
    <plugin
      filename="gz-sim-sensors-system"
      name="gz::sim::systems::Sensors">
      <render_engine>ogre2</render_engine>
    </plugin>

    <!-- Plugin for IMU -->
    <plugin filename="gz-sim-imu-system"
      name="gz::sim::systems::Imu">
    </plugin>

    <!-- To add realistic gravity, do: 0.0 0.0 -9.8, otherwise do 0.0 0.0 0.0 -->
    <gravity>0.0 0.0 -9.8</gravity>

    <!-- Include a model of the Sun from an external URI -->
    <include>
      <uri>
        https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun
      </uri>
    </include>

    <!-- Local Ground Plane with modified friction -->
    <model name="ground_plane">
      <static>true</static>
      <link name="link">
        <collision name="collision">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
            </plane>
          </geometry>
          <surface>
            <friction>
              <torsional>
                <coefficient>0.0</coefficient>
              </torsional>
            </friction>
          </surface>
        </collision>
        <visual name="visual">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
          <material>
            <ambient>0.8 0.8 0.8 1</ambient>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.8 0.8 0.8 1</specular>
          </material>
        </visual>
      </link>
    </model>

    <!-- Define scene properties -->
    <scene>
      <shadows>false</shadows>
    </scene>

  </world>
</sdf>

Save the file, and close it.

This file describes a simulated world using the Simulation Description Format (SDF) version 1.6. It defines a world named “default”. 

The world includes five important plugins: 

  1. Physics System – for simulating physics 
  2. User Commands System – for handling user inputs 
  3. Scene Broadcaster System – for broadcasting scene updates 
  4. Sensors System – for handling sensors like LIDAR 
  5. IMU System – for inertial measurement unit simulation

Gravity is set to mimic Earth’s gravity, pulling objects downward. 

Two models are brought into the world from external sources: 

  1. Sun, which provides light 
  2. Ground Plane, which gives a flat surface for objects to rest on. 

The scene settings specify that shadows should not be rendered in this world. 

This file serves as a basic template for creating a simulated environment, providing the fundamental elements needed for a functional simulation.

Now launch your Gazebo world:

cd ~/ros2_ws/src/mycobot_ros2/mycobot_gazebo/worlds/
gz sim empty.world
5-launch-empty-world

Press CTRL + C to close everything.

Now let’s create a world called house.world.

gedit house.world

Add this code.

Save the file, and close it.

Now add one more world. We will call it: pick_and_place_demo.world.

gedit pick_and_place_demo.world
<?xml version="1.0" ?>

<sdf version="1.7">
  <world name="default">

    <!-- Plugin for simulating physics -->
    <plugin
      filename="gz-sim-physics-system"
      name="gz::sim::systems::Physics">
      <engine>
        <filename>libgz-physics-bullet-featherstone-plugin.so</filename>
      </engine>
    </plugin>

    <!-- Plugin for handling user commands -->
    <plugin
      filename="gz-sim-user-commands-system"
      name="gz::sim::systems::UserCommands">
    </plugin>

    <!-- Plugin for broadcasting scene updates -->
    <plugin
      filename="gz-sim-scene-broadcaster-system"
      name="gz::sim::systems::SceneBroadcaster">
    </plugin>

    <!-- Plugin for sensor handling -->
    <plugin
      filename="gz-sim-sensors-system"
      name="gz::sim::systems::Sensors">
      <render_engine>ogre2</render_engine>
    </plugin>

    <!-- Plugin for IMU -->
    <plugin filename="gz-sim-imu-system"
      name="gz::sim::systems::Imu">
    </plugin>

    <!-- To add realistic gravity, do: 0.0 0.0 -9.8, otherwise do 0.0 0.0 0.0 -->
    <gravity>0.0 0.0 -9.8</gravity>

    <!-- Include a model of the Sun from an external URI -->
    <include>
      <uri>
        https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun
      </uri>
    </include>

    <!-- Local Ground Plane with modified friction -->
    <model name="ground_plane">
      <static>true</static>
      <link name="link">
        <collision name="collision">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
            </plane>
          </geometry>
          <surface>
            <friction>
              <torsional>
                <coefficient>0.0</coefficient>
              </torsional>
            </friction>
          </surface>
        </collision>
        <visual name="visual">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
          <material>
            <ambient>0.8 0.8 0.8 1</ambient>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.8 0.8 0.8 1</specular>
          </material>
        </visual>
      </link>
    </model>

    <!-- Include the cylinder model -->
    <include>
      <uri>model://red_cylinder</uri>
      <name>red_cylinder</name>
      <pose>0.22 0.12 0.175 0 0 0</pose>
    </include>

    <!-- Include the other objects -->

    <include>
      <uri>model://mustard</uri>
      <pose>0.7 0.15 0.08 0 0 0</pose>
    </include>

    <include>
      <uri>model://cheezit_big_original</uri>
      <pose>0.64 0.23 0.13 1.571 0 0</pose>
    </include>

    <include>
      <uri>model://cardboard_box</uri>
      <pose>0.65 0.60 0.15 0 0 0.5</pose>
    </include>

    <include>
      <uri>model://coke_can</uri>
      <pose>0.5 0.15 0.0 0 0 2.3</pose>
    </include>

    <!-- Define scene properties -->
    <scene>
      <shadows>false</shadows>
    </scene>

  </world>
</sdf>

Now we need to add models to our models folder. Models are physical objects that will exist inside your house and pick_and_place_demo worlds. These objects include things like boxes, lamps, chairs, and tables.

Add all these models to your models folder. 

Let’s walk through one of those models. We will take a look at the refrigerator model.

The refrigerator model is defined using the Simulation Description Format (SDF) version 1.6. Here’s a breakdown of its structure:

The model is named “aws_robomaker_residential_Refrigerator_01“. It contains a single link, which represents the main body of the refrigerator.

The link has three main components:

  1. Inertial properties: A mass of 1 unit is specified, which affects how the object behaves in physical simulations.
  2. Collision geometry: This defines the shape used for collision detection. It uses a mesh file named “aws_Refrigerator_01_collision.DAE” located in the model’s meshes directory. This mesh is a simplified version of the refrigerator’s shape for efficient collision calculations.
  3. Visual geometry: This defines how the refrigerator looks in the simulation. It uses a separate mesh file named “aws_Refrigerator_01_visual.DAE“. This mesh is more detailed than the collision mesh to provide a realistic appearance.

Both the collision and visual meshes are scaled to 1:1:1, meaning they use their original size.

The visual component also includes a metadata tag specifying it belongs to layer 1, which is used for rendering or interaction purposes in the simulation environment.

Finally, the model is set to static, meaning it won’t move during the simulation. This is appropriate for a large appliance like a refrigerator that typically stays in one place.

This structure allows the simulation to efficiently handle both the physical interactions and visual representation of the refrigerator in the Gazebo virtual environment.

Oh and one other thing I should mention. DAE (Digital Asset Exchange) files, also known as COLLADA (COLLAborative Design Activity) files, can be created by various 3D modeling and animation software.

The DAE format is widely used in game development, virtual reality, augmented reality, and simulation environments because it’s an open standard that can store 3D assets along with their associated metadata.

For the specific refrigerator model mentioned in the SDF file, it was likely created using a 3D modeling software as part of the AWS RoboMaker residential models set. The modelers would have created both a detailed visual mesh and a simplified collision mesh, exporting each as separate DAE files for use in the simulation environment.

The model.sdf and model.config files are typically created manually using a basic text editor.

To see your house.world file in action, move to the worlds folder in the terminal.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_gazebo/worlds/

Type the following command to let Gazebo know how to find the models:

export GZ_SIM_RESOURCE_PATH=/home/ubuntu/ros2_ws/src/mycobot_ros2/mycobot_gazebo/models

Now launch your Gazebo world. Be patient. It takes a while to load. If prompted, click “Wait”. Do not click “Force Quit.”

gz sim house.world
6-launch-house-world

Now type:

gz sim pick_and_place_demo.world

Press CTRL + C to close.

Connect Gazebo to ROS 2 Control 

Create a YAML Configuration File for the Controller Manager

After setting up our simulation environment in Gazebo, we need to tell ROS 2 Control how to manage our robot’s movements in this virtual world. Let’s create a configuration file that defines how our robot’s joints should be controlled.

The configuration file acts as a bridge between Gazebo and ROS 2, defining:

  • How often the controllers should update (100Hz)
  • Which joints can move
  • How these joints should move (position, velocity, etc.)
  • What kind of feedback the system should provide

Think of this file as a manual that tells Gazebo:

  1. What parts of your robot can move
  2. How they’re allowed to move
  3. How to report back the robot’s current state

This configuration is essential because it ensures your simulated robot behaves similarly to how a real robot would respond to commands. 

Open a terminal window, and type:

cd ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config/
mkdir -p config/mycobot_280

Create a new file inside the config/mycobot_280 directory called:

ros2_controllers.yaml

Add this code:

# controller_manager provides the necessary infrastructure to manage multiple controllers
# efficiently and robustly using ROS 2 Control.
controller_manager:
  ros__parameters:
    update_rate: 100 # update_rate specifies how often (in Hz) the controllers should be updated.

    # The JointTrajectoryController allows you to send joint trajectory commands to a group
    # of joints on a robot. These commands specify the desired positions for each joint.
    arm_controller:
      type: joint_trajectory_controller/JointTrajectoryController

    # Controls the gripper
    gripper_action_controller:
      type: position_controllers/GripperActionController

    # Responsible for publishing the current state of the robot's
    # joints to the /joint_states ROS 2 topic
    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

# Define the parameters for each controller
arm_controller:
  ros__parameters:
    joints:
      - link1_to_link2
      - link2_to_link3
      - link3_to_link4
      - link4_to_link5
      - link5_to_link6
      - link6_to_link6_flange

    # The controller will expect position commands as input for each of these joints.
    command_interfaces:
      - position

    # Tells the controller that it should expect to receive position data as the state
    # feedback from the hardware interface.
    state_interfaces:
      - position

    # If true, When set to true, the controller will not use any feedback from the system
    # (e.g., joint positions, velocities, efforts) to compute the control commands.
    open_loop_control: false

    # When set to true, it allows the controller to integrate the trajectory goals it receives.
    # This means that if the goal trajectory only specifies positions, the controller will
    # numerically integrate the positions to compute the velocities and accelerations required
    # to follow the trajectory.
    allow_integration_in_goal_trajectories: true

    # Allow non-zero velocity at the end of the trajectory
    allow_nonzero_velocity_at_trajectory_end: true

gripper_action_controller:
  ros__parameters:
    joint: gripper_controller
    action_monitor_rate: 20.0
    goal_tolerance: 0.01
    max_effort: 100.0
    allow_stalling: false
    stall_velocity_threshold: 0.001
    stall_timeout: 1.0

Save the file, and close it.

Create a new file inside the config/mycobot_280 directory called:

ros2_controllers_template.yaml
# controller_manager provides the necessary infrastructure to manage multiple controllers
# efficiently and robustly using ROS 2 Control.
controller_manager:
  ros__parameters:
    update_rate: 100 # update_rate specifies how often (in Hz) the controllers should be updated.

    # The JointTrajectoryController allows you to send joint trajectory commands to a group
    # of joints on a robot. These commands specify the desired positions for each joint.
    arm_controller:
      type: joint_trajectory_controller/JointTrajectoryController

    # Controls the gripper
    gripper_action_controller:
      type: position_controllers/GripperActionController

    # Responsible for publishing the current state of the robot's
    # joints to the /joint_states ROS 2 topic
    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

# Define the parameters for each controller
arm_controller:
  ros__parameters:
    joints:
      - ${prefix}link1_to_${prefix}link2
      - ${prefix}link2_to_${prefix}link3
      - ${prefix}link3_to_${prefix}link4
      - ${prefix}link4_to_${prefix}link5
      - ${prefix}link5_to_${prefix}link6
      - ${prefix}link6_to_${prefix}${flange_link}

    # The controller will expect position commands as input for each of these joints.
    command_interfaces:
      - position

    # Tells the controller that it should expect to receive position data as the state
    # feedback from the hardware interface.
    state_interfaces:
      - position

    # If true, When set to true, the controller will not use any feedback from the system
    # (e.g., joint positions, velocities, efforts) to compute the control commands.
    open_loop_control: false

    # When set to true, it allows the controller to integrate the trajectory goals it receives.
    # This means that if the goal trajectory only specifies positions, the controller will
    # numerically integrate the positions to compute the velocities and accelerations required
    # to follow the trajectory.
    allow_integration_in_goal_trajectories: true

    # Allow non-zero velocity at the end of the trajectory
    allow_nonzero_velocity_at_trajectory_end: true

gripper_action_controller:
  ros__parameters:
    joint: ${prefix}gripper_controller
    action_monitor_rate: 20.0
    goal_tolerance: 0.01
    max_effort: 100.0
    allow_stalling: false
    stall_velocity_threshold: 0.001
    stall_timeout: 1.0

This file will help us substitute a prefix (e.g. “left” or “right”) should we desire, for example.

Update CMakeLists.txt with the new config folder. Here is CMakeLists.txt for the mycobot_moveit_config package.

cmake_minimum_required(VERSION 3.8)
project(mycobot_moveit_config)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

# Copy necessary files to designated locations in the project
install (
  DIRECTORY config launch
  DESTINATION share/${PROJECT_NAME}
)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

Also update mycobot_desciption/launch/robot_state_publisher.py with the relevant part to handle the finding and replacing.

#!/usr/bin/env python3
"""
Launch RViz visualization for the mycobot robot.

This launch file sets up the complete visualization environment for the mycobot robot,
including robot state publisher, joint state publisher, and RViz2. It handles loading
and processing of URDF/XACRO files and controller configurations.

:author: Addison Sears-Collins
:date: November 15, 2024
"""
import os
from pathlib import Path
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterValue
from launch_ros.substitutions import FindPackageShare


def process_ros2_controllers_config(context):
    """Process the ROS 2 controller configuration yaml file before loading the URDF.

    This function reads a template configuration file, replaces placeholder values
    with actual configuration, and writes the processed file to both source and
    install directories.

    Args:
        context: Launch context containing configuration values

    Returns:
        list: Empty list as required by OpaqueFunction
    """

    # Get the configuration values
    prefix = LaunchConfiguration('prefix').perform(context)
    flange_link = LaunchConfiguration('flange_link').perform(context)
    robot_name = LaunchConfiguration('robot_name').perform(context)

    home = str(Path.home())

    # Define both source and install paths
    src_config_path = os.path.join(
        home,
        'ros2_ws/src/mycobot_ros2/mycobot_moveit_config/config',
        robot_name
    )
    install_config_path = os.path.join(
        home,
        'ros2_ws/install/mycobot_moveit_config/share/mycobot_moveit_config/config',
        robot_name
    )

    # Read from source template
    template_path = os.path.join(src_config_path, 'ros2_controllers_template.yaml')
    with open(template_path, 'r', encoding='utf-8') as file:
        template_content = file.read()

    # Create processed content (leaving template untouched)
    processed_content = template_content.replace('${prefix}', prefix)
    processed_content = processed_content.replace('${flange_link}', flange_link)

    # Write processed content to both source and install directories
    for config_path in [src_config_path, install_config_path]:
        os.makedirs(config_path, exist_ok=True)
        output_path = os.path.join(config_path, 'ros2_controllers.yaml')
        with open(output_path, 'w', encoding='utf-8') as file:
            file.write(processed_content)

    return []


# Define the arguments for the XACRO file
ARGUMENTS = [
    DeclareLaunchArgument('robot_name', default_value='mycobot_280',
                          description='Name of the robot'),
    DeclareLaunchArgument('prefix', default_value='',
                          description='Prefix for robot joints and links'),
    DeclareLaunchArgument('add_world', default_value='true',
                          choices=['true', 'false'],
                          description='Whether to add world link'),
    DeclareLaunchArgument('base_link', default_value='base_link',
                          description='Name of the base link'),
    DeclareLaunchArgument('base_type', default_value='g_shape',
                          description='Type of the base'),
    DeclareLaunchArgument('flange_link', default_value='link6_flange',
                          description='Name of the flange link'),
    DeclareLaunchArgument('gripper_type', default_value='adaptive_gripper',
                          description='Type of the gripper'),
    DeclareLaunchArgument('use_gazebo', default_value='false',
                          choices=['true', 'false'],
                          description='Whether to use Gazebo simulation'),
    DeclareLaunchArgument('use_gripper', default_value='true',
                          choices=['true', 'false'],
                          description='Whether to attach a gripper')
]


def generate_launch_description():
    """Generate the launch description for the mycobot robot visualization.

    This function sets up all necessary nodes and parameters for visualizing
    the mycobot robot in RViz, including:
    - Robot state publisher for broadcasting transforms
    - Joint state publisher for simulating joint movements
    - RViz for visualization

    Returns:
        LaunchDescription: Complete launch description for the visualization setup
    """
    # Define filenames
    urdf_package = 'mycobot_description'
    urdf_filename = 'mycobot_280.urdf.xacro'
    rviz_config_filename = 'mycobot_280_description.rviz'

    # Set paths to important files
    pkg_share_description = FindPackageShare(urdf_package)
    default_urdf_model_path = PathJoinSubstitution(
        [pkg_share_description, 'urdf', 'robots', urdf_filename])
    default_rviz_config_path = PathJoinSubstitution(
        [pkg_share_description, 'rviz', rviz_config_filename])

    # Launch configuration variables
    jsp_gui = LaunchConfiguration('jsp_gui')
    rviz_config_file = LaunchConfiguration('rviz_config_file')
    urdf_model = LaunchConfiguration('urdf_model')
    use_rviz = LaunchConfiguration('use_rviz')
    use_sim_time = LaunchConfiguration('use_sim_time')

    # Declare the launch arguments
    declare_jsp_gui_cmd = DeclareLaunchArgument(
        name='jsp_gui',
        default_value='true',
        choices=['true', 'false'],
        description='Flag to enable joint_state_publisher_gui')

    declare_rviz_config_file_cmd = DeclareLaunchArgument(
        name='rviz_config_file',
        default_value=default_rviz_config_path,
        description='Full path to the RVIZ config file to use')

    declare_urdf_model_path_cmd = DeclareLaunchArgument(
        name='urdf_model',
        default_value=default_urdf_model_path,
        description='Absolute path to robot urdf file')

    declare_use_rviz_cmd = DeclareLaunchArgument(
        name='use_rviz',
        default_value='true',
        description='Whether to start RVIZ')

    declare_use_sim_time_cmd = DeclareLaunchArgument(
        name='use_sim_time',
        default_value='false',
        description='Use simulation (Gazebo) clock if true')

    robot_description_content = ParameterValue(Command([
        'xacro', ' ', urdf_model, ' ',
        'robot_name:=', LaunchConfiguration('robot_name'), ' ',
        'prefix:=', LaunchConfiguration('prefix'), ' ',
        'add_world:=', LaunchConfiguration('add_world'), ' ',
        'base_link:=', LaunchConfiguration('base_link'), ' ',
        'base_type:=', LaunchConfiguration('base_type'), ' ',
        'flange_link:=', LaunchConfiguration('flange_link'), ' ',
        'gripper_type:=', LaunchConfiguration('gripper_type'), ' ',
        'use_gazebo:=', LaunchConfiguration('use_gazebo'), ' ',
        'use_gripper:=', LaunchConfiguration('use_gripper')
    ]), value_type=str)

    # Subscribe to the joint states of the robot, and publish the 3D pose of each link.
    start_robot_state_publisher_cmd = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        name='robot_state_publisher',
        output='screen',
        parameters=[{
            'use_sim_time': use_sim_time,
            'robot_description': robot_description_content}])

    # Publish the joint state values for the non-fixed joints in the URDF file.
    start_joint_state_publisher_cmd = Node(
        package='joint_state_publisher',
        executable='joint_state_publisher',
        name='joint_state_publisher',
        parameters=[{'use_sim_time': use_sim_time}],
        condition=UnlessCondition(jsp_gui))

    # Depending on gui parameter, either launch joint_state_publisher or joint_state_publisher_gui
    start_joint_state_publisher_gui_cmd = Node(
        package='joint_state_publisher_gui',
        executable='joint_state_publisher_gui',
        name='joint_state_publisher_gui',
        parameters=[{'use_sim_time': use_sim_time}],
        condition=IfCondition(jsp_gui))

    # Launch RViz
    start_rviz_cmd = Node(
        condition=IfCondition(use_rviz),
        package='rviz2',
        executable='rviz2',
        name='rviz2',
        output='screen',
        arguments=['-d', rviz_config_file],
        parameters=[{'use_sim_time': use_sim_time}])

    # Create the launch description and populate
    ld = LaunchDescription(ARGUMENTS)

    # Process the controller configuration before starting nodes
    ld.add_action(OpaqueFunction(function=process_ros2_controllers_config))

    # Declare the launch options
    ld.add_action(declare_jsp_gui_cmd)
    ld.add_action(declare_rviz_config_file_cmd)
    ld.add_action(declare_urdf_model_path_cmd)
    ld.add_action(declare_use_rviz_cmd)
    ld.add_action(declare_use_sim_time_cmd)

    # Add any actions
    ld.add_action(start_joint_state_publisher_cmd)
    ld.add_action(start_joint_state_publisher_gui_cmd)
    ld.add_action(start_robot_state_publisher_cmd)
    ld.add_action(start_rviz_cmd)

    return ld

Let’s discuss the key components of the configuration files.

Controller Manager

The controller manager acts as the central orchestrator, running at 100Hz to manage multiple controllers simultaneously. This high update rate ensures smooth motion control and responsive behavior of the robot.

Arm Controller (JointTrajectoryController)

This controller handles the coordinated motion of the robot’s six-axis arm. It uses a joint trajectory controller implementation, which means it can process complex movement paths while maintaining synchronization between joints. The controller operates in closed-loop mode (open_loop_control: false), utilizing position feedback to ensure accurate movement.

The arm configuration shows six joints, connecting from link1 through to the flange link. Each joint accepts position commands and reports back its current position state. The controller supports trajectory integration, meaning it can calculate required velocities and accelerations from position-only commands, and allows for trajectories that end with non-zero velocities.

Gripper Controller

The gripper uses a position-based action controller, monitoring its state at 20Hz. It includes practical safety features like:

  • A goal tolerance of 0.01 units
  • Maximum effort limit of 100 units
  • Stall detection (if movement falls below 0.001 units/s for more than 1 second)

Joint State Broadcaster

This component publishes the real-time state of all joints to ROS 2’s joint_states topic, enabling other nodes in the system to monitor the robot’s current configuration. This is important for tasks like collision checking, visualization, and coordinated motion planning.

The configuration uses parameter substitution (indicated by ${prefix}) to allow for flexible naming schemes, which is particularly useful when deploying the same configuration across different robot instances or configurations.

Each controller is defined with specific interfaces for commands and state feedback, establishing a clear contract for how the controller interacts with the hardware layer of the robot.

Create the XACRO/URDF Files

Next, we need to add two essential XACRO/URDF files that bridge Gazebo simulation with ROS 2 Control. These files work alongside your controller configuration YAML file to create a complete control system.

The first file creates a connection between Gazebo and ROS 2 control: 

gazebo_sim_ros2_control.urdf.xacro

The second file is the instruction manual for using that connection: 

mycobot_280_ros2_control.urdf.xacro

Without the first file, Gazebo wouldn’t know to use ROS 2 Control. Without the second file, ROS 2 Control wouldn’t know how to control the robot’s joints.

gazebo_sim_ros2_control.urdf.xacro

  • Loads the Gazebo ROS 2 Control plugin
  • Points Gazebo to your controller settings file (mycobot_280_controllers.yaml)
  • Makes sure ROS 2 and Gazebo can communicate properly
  • Think of this as the “middle man” between Gazebo and ROS 2 Control
  • Without this file, Gazebo wouldn’t know to accept ROS 2 commands

Open a terminal window.

Type the following command:

cd ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/
mkdir control

Create the file named:

gazebo_sim_ros2_control.urdf.xacro

Add this code.

<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
    <xacro:macro name="load_gazebo_sim_ros2_control_plugin" params="robot_name use_gazebo">
        <xacro:if value="${use_gazebo}">
            <gazebo>
                <plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
                    <parameters>$(find mycobot_moveit_config)/config/${robot_name}/ros2_controllers.yaml</parameters>
                    <ros>
                        <remapping>/controller_manager/robot_description:=/robot_description</remapping>
                    </ros>
                </plugin>
            </gazebo>
        </xacro:if>
    </xacro:macro>
</robot>

Save the file, and close it.

mycobot_280_ros2_control.urdf.xacro:

  • The main robot control “instruction manual”
  • Sets up two important interfaces for each joint:
    • Command interface: How you send desired angles to each joint (like “move to 45 degrees”)
    • State interface: How you read back what angle each joint is currently at
  • Defines safe movement limits for each joint
  • Tells the gripper joints how to move together (mimic joints)
  • Think of this as defining “what each part can do and how to do it”

Open a terminal window.

Type the following command:

cd ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/control

Create the file named:

mycobot_280_ros2_control.urdf.xacro

Add this code.

<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">

    <xacro:macro name="mycobot_ros2_control" params="prefix flange_link use_gazebo">
        <ros2_control name="RobotSystem" type="system">
            <hardware>
                <xacro:if value="${use_gazebo}">
                    <plugin>gz_ros2_control/GazeboSimSystem</plugin>
                </xacro:if>
            </hardware>

            <joint name="${prefix}link1_to_${prefix}link2">
                <command_interface name="position">
                    <param name="min">-2.879793</param>
                    <param name="max">2.879793</param>
                </command_interface>
                <state_interface name="position"/>
            </joint>

            <joint name="${prefix}link2_to_${prefix}link3">
                <command_interface name="position">
                    <param name="min">-2.879793</param>
                    <param name="max">2.879793</param>
                </command_interface>
                <state_interface name="position"/>
            </joint>

            <joint name="${prefix}link3_to_${prefix}link4">
                <command_interface name="position">
                    <param name="min">-2.879793</param>
                    <param name="max">2.879793</param>
                </command_interface>
                <state_interface name="position"/>
            </joint>

            <joint name="${prefix}link4_to_${prefix}link5">
                <command_interface name="position">
                    <param name="min">-2.879793</param>
                    <param name="max">2.879793</param>
                </command_interface>
                <state_interface name="position"/>
            </joint>

            <joint name="${prefix}link5_to_${prefix}link6">
                <command_interface name="position">
                    <param name="min">-2.879793</param>
                    <param name="max">2.879793</param>
                </command_interface>
                <state_interface name="position"/>
            </joint>

            <joint name="${prefix}link6_to_${prefix}${flange_link}">
                <command_interface name="position">
                    <param name="min">-3.05</param>
                    <param name="max">3.05</param>
                </command_interface>
                <state_interface name="position"/>
            </joint>

            <joint name="${prefix}gripper_controller">
                <command_interface name="position">
                    <param name="min">-0.7</param>
                    <param name="max">0.15</param>
                </command_interface>
                <state_interface name="position"/>
                <state_interface name="velocity"/>
            </joint>

            <joint name="${prefix}gripper_base_to_${prefix}gripper_left2">
                <param name="mimic">gripper_controller</param>
                <param name="multiplier">1.0</param>
                <state_interface name="position"/>
                <state_interface name="velocity"/>
            </joint>

            <joint name="${prefix}gripper_left3_to_${prefix}gripper_left1">
                <param name="mimic">gripper_controller</param>
                <param name="multiplier">-1.0</param>
                <state_interface name="position"/>
                <state_interface name="velocity"/>
            </joint>

            <joint name="${prefix}gripper_base_to_${prefix}gripper_right3">
                <param name="mimic">gripper_controller</param>
                <param name="multiplier">-1.0</param>
                <state_interface name="position"/>
                <state_interface name="velocity"/>
            </joint>

            <joint name="${prefix}gripper_base_to_${prefix}gripper_right2">
                <param name="mimic">gripper_controller</param>
                <state_interface name="position"/>
                <state_interface name="velocity"/>
            </joint>

            <joint name="${prefix}gripper_right3_to_${prefix}gripper_right1">
                <param name="mimic">gripper_controller</param>
                <param name="multiplier">1.0</param>
                <state_interface name="position"/>
                <state_interface name="velocity"/>
            </joint>

        </ros2_control>
    </xacro:macro>

</robot>

Save the file, and close it.

Include the Files in mycobot_280.urdf.xacro

Next we need to include these files inside mycobot_280.urdf.xacro.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/robots/

Open the mycobot_280_urdf.xacro file.

Add this code at the bottom of the file:

    <xacro:include filename="$(find mycobot_description)/urdf/control/gazebo_sim_ros2_control.urdf.xacro" />
    <xacro:load_gazebo_sim_ros2_control_plugin
      robot_name="$(arg robot_name)"
      use_gazebo="$(arg use_gazebo)"/>

   <xacro:include filename="$(find mycobot_description)/urdf/control/mycobot_280_ros2_control.urdf.xacro" />
    <xacro:mycobot_ros2_control
      prefix="$(arg prefix)"
      flange_link="$(arg flange_link)"
      use_gazebo="$(arg use_gazebo)"/>

Create the Launch Files

Now let’s create the launch files.

load_ros2_controllers.launch.py

cd  ~/ros2_ws/src/mycobot_ros2/mycobot_moveit_config/
mkdir launch
cd launch

Add this code called load_ros2_controllers.launch.py:

#!/usr/bin/env python3
"""
Launch ROS 2 controllers for the robot.

This script creates a launch description that starts the necessary controllers
for operating the robotic arm and gripper in a specific sequence.

Launched Controllers:
    1. Joint State Broadcaster: Publishes joint states to /joint_states
    2. Arm Controller: Controls the robot arm movements via /follow_joint_trajectory
    3. Gripper Action Controller: Controls gripper actions via /gripper_action

Launch Sequence:
    1. Joint State Broadcaster
    2. Arm Controller (starts after Joint State Broadcaster)
    3. Gripper Action Controller (starts after Arm Controller)

:author: Addison Sears-Collins
:date: November 15, 2024
"""

from launch import LaunchDescription
from launch.actions import ExecuteProcess, RegisterEventHandler
from launch.event_handlers import OnProcessExit


def generate_launch_description():
    """Generate a launch description for sequentially starting robot controllers.

    Returns:
        LaunchDescription: Launch description containing sequenced controller starts
    """
    # Start arm controller
    start_arm_controller_cmd = ExecuteProcess(
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
             'arm_controller'],
        output='screen')

    # Start gripper action controller
    start_gripper_action_controller_cmd = ExecuteProcess(
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
             'gripper_action_controller'],
        output='screen')

    # Launch joint state broadcaster
    start_joint_state_broadcaster_cmd = ExecuteProcess(
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
             'joint_state_broadcaster'],
        output='screen')

    # Register event handlers for sequencing
    # Launch the joint state broadcaster after spawning the robot
    load_joint_state_broadcaster_cmd = RegisterEventHandler(
        event_handler=OnProcessExit(
            target_action=start_joint_state_broadcaster_cmd,
            on_exit=[start_arm_controller_cmd]))

    # Launch the arm controller after launching the joint state broadcaster
    load_arm_controller_cmd = RegisterEventHandler(
        event_handler=OnProcessExit(
            target_action=start_arm_controller_cmd,
            on_exit=[start_gripper_action_controller_cmd]))

    # Create the launch description and populate
    ld = LaunchDescription()

    # Add the actions to the launch description in sequence
    ld.add_action(start_joint_state_broadcaster_cmd)
    ld.add_action(load_joint_state_broadcaster_cmd)
    ld.add_action(load_arm_controller_cmd)

    return ld

Update CMakeLists.txt for the mycobot_moveit_config package to include the new launch folder. Make sure the block below, looks like this:

# Copy necessary files to designated locations in the project
install (
  DIRECTORY config launch
  DESTINATION share/${PROJECT_NAME}
)

mycobot.gazebo.launch.py

cd ~/ros2_ws/src/mycobot_ros2/mycobot_gazebo/launch

Create a new file called mycobot.gazebo.launch.py.

Add this code, and save the file.

Create a Bash Script for Quick Launching

Create a bash script to launch multiple launch files:

cd  ~/ros2_ws/src/mycobot_ros2/mycobot_bringup/
mkdir scripts

Add a bash file called: mycobot_280_gazebo.sh.

Add this code:

#!/bin/bash
# Single script to launch the myCobot with Gazebo and ROS 2 Controllers

cleanup() {
    echo "Cleaning up..."
    echo "Restarting ROS 2 daemon..."
    ros2 daemon stop
    sleep 1
    ros2 daemon start
    echo "Terminating all ROS 2-related processes..."
    kill 0
    exit
}

# Set up cleanup trap
trap 'cleanup' SIGINT

echo "Launching Gazebo simulation..."
ros2 launch mycobot_gazebo mycobot.gazebo.launch.py \
    load_controllers:=true \
    world_file:=pick_and_place_demo.world \
    use_rviz:=true \
    use_robot_state_pub:=true \
    use_sim_time:=true \
    x:=0.0 \
    y:=0.0 \
    z:=0.05 \
    roll:=0.0 \
    pitch:=0.0 \
    yaw:=0.0

Save the file, and close it.

Make it executable.

sudo chmod +x mycobot_280_gazebo.sh

I will add an alias for quick launch:

echo "alias robot='bash ~/ros2_ws/src/mycobot_ros2/mycobot_bringup/scripts/mycobot_280_gazebo.sh'" >> ~/.bashrc && source ~/.bashrc

Make sure to update CMakeLists.txt for the mycobot_bringup folder.

Update CMakeLists.txt

Go to the CMakeLists.txt.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_gazebo/

Make sure it has this block of code:

# Copy necessary files to designated locations in the project
install (
  DIRECTORY launch models worlds
  DESTINATION share/${PROJECT_NAME}
)
gedit CMakeLists.txt

Save the file, and close it.

Build the Workspace

Now let’s build the package. Open a terminal window, and type:

build

Launch Everything and Move the Arm

Now let’s launch everything.

Open a terminal window, and type the following command:

robot

OR

bash ~/ros2_ws/src/mycobot_ros2/mycobot_bringup/scripts/mycobot_280_gazebo.sh

Here is the output using the empty.world file:

7-gazebo-rviz

To see a list of active Gazebo topics, type:

gz topic -l

To see the options, you can type:

gz topic -help

See the active controllers:

ros2 control list_controllers

To get more information, type:

ros2 control list_controllers -v

If you want to close the gripper, you can do this:

ros2 action send_goal /gripper_action_controller/gripper_cmd control_msgs/action/GripperCommand "{command: {position: -0.7, max_effort: 5.0}}"

If you want to open the gripper, you can do this:

ros2 action send_goal /gripper_action_controller/gripper_cmd control_msgs/action/GripperCommand "{command: {position: 0.0, max_effort: 5.0}}"

Deactivate the gripper_action_controller (which uses the position_controllers/GripperActionController interface…we will use this in a later tutorial)

ros2 control set_controller_state gripper_action_controller inactive

To see a list of all the commands you can use type:

ros2 control 

Then press Tab twice.

List all the available hardware components that are loaded and ready to be used by the ros2_control controller manager.

ros2 control list_hardware_components

Now let’s send a command to the robotic arm to move it.

Let’s check out the topics:

ros2 topic list

We need this topic: /arm_controller/joint_trajectory

We can publish a trajectory to that topic to move the arm. Let’s get more information about the topic:

ros2 topic info /arm_controller/joint_trajectory

We need we to publish a message of type:

trajectory_msgs/msg/JointTrajectory

Remember, here were the list of joints that are controlled by the arm_controller:

  • link1_to_link2
  • link2_to_link3
  • link3_to_link4
  • link4_to_link5
  • link5_to_link6
  • link6_to_link6_flange

There are 6 joints in total.

Here is a command you can use to move the arm (this is all a single command):

ros2 topic pub --once /arm_controller/joint_trajectory trajectory_msgs/msg/JointTrajectory "{joint_names: ['link1_to_link2', 'link2_to_link3', 'link3_to_link4', 'link4_to_link5', 'link5_to_link6', 'link6_to_link6_flange'], points: [{positions: [1.345, -1.23, 0.264, -0.296, 0.389, -1.5], time_from_start: {sec: 3.0, nanosec: 0}}]}"

OR

ros2 action send_goal /arm_controller/follow_joint_trajectory control_msgs/action/FollowJointTrajectory "{
  trajectory: {
    joint_names: ['link1_to_link2', 'link2_to_link3', 'link3_to_link4', 'link4_to_link5', 'link5_to_link6', 'link6_to_link6_flange'],
    points: [{
      positions: [1.345, -1.23, 0.264, -0.296, 0.389, -1.5],
      velocities: [],
      accelerations: [],
      effort: [],
      time_from_start: {sec: 3, nanosec: 0}
    }]
  }
}"

You can also move it back home now:

ros2 topic pub --once /arm_controller/joint_trajectory trajectory_msgs/msg/JointTrajectory "{joint_names: ['link1_to_link2', 'link2_to_link3', 'link3_to_link4', 'link4_to_link5', 'link5_to_link6', 'link6_to_link6_flange'], points: [{positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], time_from_start: {sec: 1.5, nanosec: 0}}]}"

OR

ros2 action send_goal /arm_controller/follow_joint_trajectory control_msgs/action/FollowJointTrajectory "{
  trajectory: {
    joint_names: ['link1_to_link2', 'link2_to_link3', 'link3_to_link4', 'link4_to_link5', 'link5_to_link6', 'link6_to_link6_flange'],
    points: [{
      positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
      velocities: [],
      accelerations: [],
      effort: [],
      time_from_start: {sec: 1, nanosec: 500000000}
    }]
  }
}"

Move the Robotic Arm Using Code

Let’s create a ROS 2 node that can loop through a list of trajectories to simulate the arm moving from the home position to a goal location and then back to home.

Python

Let’s start by creating a script using Python.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_system_tests/
mkdir scripts

Create a new file called: arm_gripper_loop_controller.py

#!/usr/bin/env python3
"""
Control robot arm and gripper to perform repetitive movements between positions.

This script creates a ROS 2 node that moves a robot arm between target and home positions,
coordinating with gripper actions (open/close) at each position. The movement happens
in a continuous loop.

Action Clients:
    /arm_controller/follow_joint_trajectory (control_msgs/FollowJointTrajectory):
        Commands for controlling arm joint positions
    /gripper_action_controller/gripper_cmd (control_msgs/GripperCommand):
        Commands for opening and closing the gripper

:author: Addison Sears-Collins
:date: November 15, 2024
"""

import time
import rclpy
from rclpy.node import Node
from rclpy.action import ActionClient
from control_msgs.action import FollowJointTrajectory, GripperCommand
from trajectory_msgs.msg import JointTrajectoryPoint
from builtin_interfaces.msg import Duration


class ArmGripperLoopController(Node):
    """
    A ROS 2 node for controlling robot arm movements and gripper actions.

    This class creates a simple control loop that:
    1. Moves the arm to a target position
    2. Closes the gripper
    3. Returns the arm to home position
    4. Opens the gripper
    """

    def __init__(self):
        """
        Initialize the node and set up action clients for arm and gripper control.

        Sets up two action clients:
        - One for controlling arm movements
        - One for controlling gripper open/close actions
        Also defines the positions for movement and starts a timer for the control loop.
        """
        super().__init__('arm_gripper_loop_controller')

        # Set up arm trajectory action client for arm movement control
        self.arm_client = ActionClient(
            self,
            FollowJointTrajectory,
            '/arm_controller/follow_joint_trajectory'
        )

        # Set up gripper action client for gripper control
        self.gripper_client = ActionClient(
            self,
            GripperCommand,
            '/gripper_action_controller/gripper_cmd'
        )

        # Wait for both action servers to be available
        self.get_logger().info('Waiting for action servers...')
        self.arm_client.wait_for_server()
        self.gripper_client.wait_for_server()
        self.get_logger().info('Action servers connected!')

        # List of joint names for the robot arm
        self.joint_names = [
            'link1_to_link2', 'link2_to_link3', 'link3_to_link4',
            'link4_to_link5', 'link5_to_link6', 'link6_to_link6_flange'
        ]

        # Define target and home positions for the arm
        self.target_pos = [1.345, -1.23, 0.264, -0.296, 0.389, -1.5]
        self.home_pos = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

        # Create timer that triggers the control loop quickly after start (0.1 seconds)
        self.create_timer(0.1, self.control_loop_callback)

    def send_arm_command(self, positions: list) -> None:
        """
        Send a command to move the robot arm to specified joint positions.

        Args:
            positions (list): List of 6 joint angles in radians
        """
        # Create a trajectory point with the target positions
        point = JointTrajectoryPoint()
        point.positions = positions
        point.time_from_start = Duration(sec=2)  # Allow 2 seconds for movement

        # Create and send the goal message
        goal_msg = FollowJointTrajectory.Goal()
        goal_msg.trajectory.joint_names = self.joint_names
        goal_msg.trajectory.points = [point]

        self.arm_client.send_goal_async(goal_msg)

    def send_gripper_command(self, position: float) -> None:
        """
        Send a command to the gripper to open or close.

        Args:
            position (float): Position value for gripper (0.0 for open, -0.7 for closed)
        """
        # Create and send the gripper command
        goal_msg = GripperCommand.Goal()
        goal_msg.command.position = position
        goal_msg.command.max_effort = 5.0

        self.gripper_client.send_goal_async(goal_msg)

    def control_loop_callback(self) -> None:
        """
        Execute one cycle of the control loop.

        This method performs the following sequence:
        1. Move arm to target position
        2. Pause at target
        3. Close gripper
        4. Move arm to home position
        5. Pause at home
        6. Open gripper
        7. Pause before next cycle
        """
        # Move to target position
        self.get_logger().info('Moving to target position')
        self.send_arm_command(self.target_pos)
        time.sleep(2.5)  # Wait for arm to reach target (2.5s)

        # Pause at target position
        self.get_logger().info('Reached target position - Pausing')
        time.sleep(1.0)  # Pause for 1 second at target

        # Close gripper
        self.get_logger().info('Closing gripper')
        self.send_gripper_command(-0.7)  # Close gripper
        time.sleep(0.5)  # Wait for gripper to close

        # Move to home position
        self.get_logger().info('Moving to home position')
        self.send_arm_command(self.home_pos)
        time.sleep(2.5)  # Wait for arm to reach home (2.5s)

        # Pause at home position
        self.get_logger().info('Reached home position - Pausing')
        time.sleep(1.0)  # Pause for 1 second at home

        # Open gripper
        self.get_logger().info('Opening gripper')
        self.send_gripper_command(0.0)  # Open gripper
        time.sleep(0.5)  # Wait for gripper to open

        # Final pause before next cycle
        time.sleep(1.0)


def main(args=None):
    """
    Initialize and run the arm gripper control node.

    Args:
        args: Command-line arguments (default: None)
    """
    rclpy.init(args=args)
    controller = ArmGripperLoopController()

    try:
        rclpy.spin(controller)
    except KeyboardInterrupt:
        controller.get_logger().info('Shutting down arm gripper controller...')
    finally:
        controller.destroy_node()
        rclpy.shutdown()


if __name__ == '__main__':
    main()

Update to your CMakeLists.txt file with the new script.

build

Launch your arm in Gazebo:

robot

Now run your node:

ros2 run mycobot_system_tests arm_gripper_loop_controller.py

The robot will move from the home position to the target position in a loop until you press CTRL + C.

C++

Now let’s create the same node in C++.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_system_tests/src

Add a file called arm_gripper_loop_controller.cpp.

Update your CMakeLists.txt file and package.xml file.

build

Launch your arm in Gazebo:

robot

Now run your node:

ros2 run mycobot_system_tests  arm_gripper_loop_controller

Your robotic arm will go repeatedly from the home position to the target position.

8-house-world

Congratulations! You made it to the end. That’s it!

Keep building!

Create Launch Files to Display URDF Files – ROS 2 Jazzy

In this tutorial, I will guide you through the process of creating a custom launch file to launch a robotic arm and a mobile robot 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.

Launch files in ROS 2 are powerful tools that allow you to start multiple nodes and set parameters with a single command, simplifying the process of managing your robot’s complex systems.

Prerequisites

All my code for this project is located here on GitHub (robotic arm) and here on GitHub (mobile robot).

Create the Launch File for the Robotic Arm

Open a terminal window.

Move to your robotic arm directory.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_description/ && mkdir launch && cd launch

Add a file in the launch folder called robot_state_publisher.launch.py.

Add this code.

#!/usr/bin/env python3
#
# Author: Addison Sears-Collins
# Date: November 10, 2024
# Description: Display the robotic arm with RViz
#
# This file launches the robot state publisher, joint state publisher,
# and RViz2 for visualizing the mycobot robot.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterValue
from launch_ros.substitutions import FindPackageShare

# Define the arguments for the XACRO file
ARGUMENTS = [
    DeclareLaunchArgument('prefix', default_value='',
                          description='Prefix for robot joints and links'),
    DeclareLaunchArgument('add_world', default_value='true',
                          choices=['true', 'false'],
                          description='Whether to add world link'),
    DeclareLaunchArgument('base_link', default_value='base_link',
                          description='Name of the base link'),
    DeclareLaunchArgument('base_type', default_value='g_shape',
                          description='Type of the base'),
    DeclareLaunchArgument('flange_link', default_value='link6_flange',
                          description='Name of the flange link'),
    DeclareLaunchArgument('gripper_type', default_value='adaptive_gripper',
                          description='Type of the gripper'),
    DeclareLaunchArgument('use_gazebo', default_value='false',
                          choices=['true', 'false'],
                          description='Whether to use Gazebo simulation'),
    DeclareLaunchArgument('use_gripper', default_value='true',
                          choices=['true', 'false'],
                          description='Whether to attach a gripper')
]


def generate_launch_description():
    # Define filenames
    urdf_package = 'mycobot_description'
    urdf_filename = 'mycobot_280.urdf.xacro'
    rviz_config_filename = 'mycobot_280_description.rviz'

    # Set paths to important files
    pkg_share_description = FindPackageShare(urdf_package)
    default_urdf_model_path = PathJoinSubstitution(
        [pkg_share_description, 'urdf', 'robots', urdf_filename])
    default_rviz_config_path = PathJoinSubstitution(
        [pkg_share_description, 'rviz', rviz_config_filename])

    # Launch configuration variables
    jsp_gui = LaunchConfiguration('jsp_gui')
    rviz_config_file = LaunchConfiguration('rviz_config_file')
    urdf_model = LaunchConfiguration('urdf_model')
    use_rviz = LaunchConfiguration('use_rviz')
    use_sim_time = LaunchConfiguration('use_sim_time')

    # Declare the launch arguments
    declare_jsp_gui_cmd = DeclareLaunchArgument(
        name='jsp_gui',
        default_value='true',
        choices=['true', 'false'],
        description='Flag to enable joint_state_publisher_gui')

    declare_rviz_config_file_cmd = DeclareLaunchArgument(
        name='rviz_config_file',
        default_value=default_rviz_config_path,
        description='Full path to the RVIZ config file to use')

    declare_urdf_model_path_cmd = DeclareLaunchArgument(
        name='urdf_model',
        default_value=default_urdf_model_path,
        description='Absolute path to robot urdf file')

    declare_use_rviz_cmd = DeclareLaunchArgument(
        name='use_rviz',
        default_value='true',
        description='Whether to start RVIZ')

    declare_use_sim_time_cmd = DeclareLaunchArgument(
        name='use_sim_time',
        default_value='false',
        description='Use simulation (Gazebo) clock if true')

    robot_description_content = ParameterValue(Command([
        'xacro', ' ', urdf_model, ' ',
        'prefix:=', LaunchConfiguration('prefix'), ' ',
        'add_world:=', LaunchConfiguration('add_world'), ' ',
        'base_link:=', LaunchConfiguration('base_link'), ' ',
        'base_type:=', LaunchConfiguration('base_type'), ' ',
        'flange_link:=', LaunchConfiguration('flange_link'), ' ',
        'gripper_type:=', LaunchConfiguration('gripper_type'), ' ',
        'use_gazebo:=', LaunchConfiguration('use_gazebo'), ' ',
        'use_gripper:=', LaunchConfiguration('use_gripper')
    ]), value_type=str)

    # Subscribe to the joint states of the robot, and publish the 3D pose of each link.
    start_robot_state_publisher_cmd = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        name='robot_state_publisher',
        output='screen',
        parameters=[{
            'use_sim_time': use_sim_time,
            'robot_description': robot_description_content}])

    # Publish the joint state values for the non-fixed joints in the URDF file.
    start_joint_state_publisher_cmd = Node(
        package='joint_state_publisher',
        executable='joint_state_publisher',
        name='joint_state_publisher',
        parameters=[{'use_sim_time': use_sim_time}],
        condition=UnlessCondition(jsp_gui))

    # Depending on gui parameter, either launch joint_state_publisher or joint_state_publisher_gui
    start_joint_state_publisher_gui_cmd = Node(
        package='joint_state_publisher_gui',
        executable='joint_state_publisher_gui',
        name='joint_state_publisher_gui',
        parameters=[{'use_sim_time': use_sim_time}],
        condition=IfCondition(jsp_gui))

    # Launch RViz
    start_rviz_cmd = Node(
        condition=IfCondition(use_rviz),
        package='rviz2',
        executable='rviz2',
        name='rviz2',
        output='screen',
        arguments=['-d', rviz_config_file],
        parameters=[{'use_sim_time': use_sim_time}])

    # Create the launch description and populate
    ld = LaunchDescription(ARGUMENTS)

    # Declare the launch options
    ld.add_action(declare_jsp_gui_cmd)
    ld.add_action(declare_rviz_config_file_cmd)
    ld.add_action(declare_urdf_model_path_cmd)
    ld.add_action(declare_use_rviz_cmd)
    ld.add_action(declare_use_sim_time_cmd)

    # Add any actions
    ld.add_action(start_joint_state_publisher_cmd)
    ld.add_action(start_joint_state_publisher_gui_cmd)
    ld.add_action(start_robot_state_publisher_cmd)
    ld.add_action(start_rviz_cmd)

    return ld

Create the Launch File for the Mobile Robot

Open a terminal window.

Move to your robotic arm directory.

cd ~/ros2_ws/src/yahboom_rosmaster/yahboom_rosmaster_description/ && mkdir launch && cd launch

Add a file in the launch folder called robot_state_publisher.launch.py.

Add this code.

#!/usr/bin/env python3
#
# Author: Addison Sears-Collins
# Date: November 11, 2024
# Description: Display the Yahboom (ROSMASTER) robot in RViz
#
# This file launches the robot state publisher, joint state publisher,
# and RViz2 for visualizing the ROSMASTER robot.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterValue
from launch_ros.substitutions import FindPackageShare

# Define the arguments for the XACRO file
ARGUMENTS = [
    DeclareLaunchArgument('prefix', default_value='',
                          description='Prefix for robot joints and links'),
    DeclareLaunchArgument('use_gazebo', default_value='false',
                          choices=['true', 'false'],
                          description='Whether to use Gazebo simulation')
]


def generate_launch_description():
    # Define filenames
    urdf_package = 'yahboom_rosmaster_description'
    urdf_filename = 'rosmaster_x3.urdf.xacro'
    rviz_config_filename = 'yahboom_rosmaster_description.rviz'

    # Set paths to important files
    pkg_share_description = FindPackageShare(urdf_package)
    default_urdf_model_path = PathJoinSubstitution(
        [pkg_share_description, 'urdf', 'robots', urdf_filename])
    default_rviz_config_path = PathJoinSubstitution(
        [pkg_share_description, 'rviz', rviz_config_filename])

    # Launch configuration variables
    jsp_gui = LaunchConfiguration('jsp_gui')
    rviz_config_file = LaunchConfiguration('rviz_config_file')
    urdf_model = LaunchConfiguration('urdf_model')
    use_rviz = LaunchConfiguration('use_rviz')
    use_sim_time = LaunchConfiguration('use_sim_time')

    # Declare the launch arguments
    declare_jsp_gui_cmd = DeclareLaunchArgument(
        name='jsp_gui',
        default_value='true',
        choices=['true', 'false'],
        description='Flag to enable joint_state_publisher_gui')

    declare_rviz_config_file_cmd = DeclareLaunchArgument(
        name='rviz_config_file',
        default_value=default_rviz_config_path,
        description='Full path to the RVIZ config file to use')

    declare_urdf_model_path_cmd = DeclareLaunchArgument(
        name='urdf_model',
        default_value=default_urdf_model_path,
        description='Absolute path to robot urdf file')

    declare_use_rviz_cmd = DeclareLaunchArgument(
        name='use_rviz',
        default_value='true',
        description='Whether to start RVIZ')

    declare_use_sim_time_cmd = DeclareLaunchArgument(
        name='use_sim_time',
        default_value='false',
        description='Use simulation (Gazebo) clock if true')

    robot_description_content = ParameterValue(Command([
        'xacro', ' ', urdf_model, ' ',
        'prefix:=', LaunchConfiguration('prefix'), ' ',
        'use_gazebo:=', LaunchConfiguration('use_gazebo')
    ]), value_type=str)

    # Subscribe to the joint states of the robot, and publish the 3D pose of each link.
    start_robot_state_publisher_cmd = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        name='robot_state_publisher',
        output='screen',
        parameters=[{
            'use_sim_time': use_sim_time,
            'robot_description': robot_description_content}])

    # Publish the joint state values for the non-fixed joints in the URDF file.
    start_joint_state_publisher_cmd = Node(
        package='joint_state_publisher',
        executable='joint_state_publisher',
        name='joint_state_publisher',
        parameters=[{'use_sim_time': use_sim_time}],
        condition=UnlessCondition(jsp_gui))

    # Depending on gui parameter, either launch joint_state_publisher or joint_state_publisher_gui
    start_joint_state_publisher_gui_cmd = Node(
        package='joint_state_publisher_gui',
        executable='joint_state_publisher_gui',
        name='joint_state_publisher_gui',
        parameters=[{'use_sim_time': use_sim_time}],
        condition=IfCondition(jsp_gui))

    # Launch RViz
    start_rviz_cmd = Node(
        condition=IfCondition(use_rviz),
        package='rviz2',
        executable='rviz2',
        name='rviz2',
        output='screen',
        arguments=['-d', rviz_config_file],
        parameters=[{'use_sim_time': use_sim_time}])

    # Create the launch description and populate
    ld = LaunchDescription(ARGUMENTS)

    # Declare the launch options
    ld.add_action(declare_jsp_gui_cmd)
    ld.add_action(declare_rviz_config_file_cmd)
    ld.add_action(declare_urdf_model_path_cmd)
    ld.add_action(declare_use_rviz_cmd)
    ld.add_action(declare_use_sim_time_cmd)

    # Add any actions
    ld.add_action(start_joint_state_publisher_cmd)
    ld.add_action(start_joint_state_publisher_gui_cmd)
    ld.add_action(start_robot_state_publisher_cmd)
    ld.add_action(start_rviz_cmd)

    return ld

Add the RViz Configuration File

Now that we have written our launch file, let’s add the RViz configuration file.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_description/ && mkdir rviz && cd rviz

Create a file named mycobot_280_description.rviz

Add this code.

cd ~/ros2_ws/src/yahboom_rosmaster/yahboom_rosmaster_description/ && mkdir rviz && cd rviz

Create a file named yahboom_rosmaster_description.rviz 

Add this code.

You don’t need to understand all the nitty gritty details of this configuration file. You can generate one automatically through RViz.

On a high-level, RViz configuration files end with the extension .rviz. These files set up an RViz configuration with a grid, a robot model, and coordinate frame visualizations. 

This configuration file also enables the camera movement tool and sets the initial camera view to an orbit view, which allows orbiting around a focal point in the scene. 

When RViz is launched with this configuration file, it will display the robot model and allow interaction and visualization of the robot.

Edit CMakeLists.txt

Now we need to edit CMakeLists.txt so the build system can find our new folders, launch and rviz.

cd ~/ros2_ws/src/mycobot_ros2/mycobot_description/ 
gedit CMakeLists.txt

Add this code:

# Copy necessary files to designated locations in the project
install (
  DIRECTORY launch meshes urdf rviz
  DESTINATION share/${PROJECT_NAME}
)
cd ~/ros2_ws/src/yahboom_rosmaster/yahboom_rosmaster_description/ 
gedit CMakeLists.txt

Add this code:

# Copy necessary files to designated locations in the project
install (
  DIRECTORY launch meshes urdf rviz
  DESTINATION share/${PROJECT_NAME}
)

Save the file, and close it.

Now build your workspace.

cd ~/ros2_ws/
colcon build
source ~/.bashrc

Launch the Launch Files

Launch your launch files:

ros2 launch mycobot_description robot_state_publisher.launch.py
1-mycobot-custom-launch-rviz
ros2 launch yahboom_rosmaster_description robot_state_publisher.launch.py

You can also add launch arguments. To see the available launch arguments, type:

ros2 launch mycobot_description robot_state_publisher.launch.py --show-args

For example, to disable the gripper, type:

ros2 launch mycobot_description robot_state_publisher.launch.py use_gripper:=false

To add a prefix to the robot (e.g. left arm of a dual arm robot), type:

ros2 launch mycobot_description robot_state_publisher.launch.py use_gripper:=false prefix:=left_
2-remove-gripper-and-add-prefix

If you want to launch the robots with no GUIs, do this:

ros2 launch mycobot_description robot_state_publisher.launch.py jsp_gui:=false use_rviz:=false
ros2 launch yahboom_rosmaster_description robot_state_publisher.launch.py jsp_gui:=false use_rviz:=false
3-yahboom-robot

And there you have it…your first custom launch files.

Launch File Walkthrough

Let’s walk through this ROS 2 launch file that visualizes a robotic arm in RViz.

Starting with the imports, we bring in essential ROS 2 launch utilities.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition

The launch file’s core purpose is orchestrating multiple nodes – think of it as a conductor coordinating different musicians in an orchestra. Here, our musicians are:

  • Robot State Publisher: Broadcasts the robot’s current pose
  • Joint State Publisher: Manages the robot’s joint positions
  • RViz: Provides the 3D visualization

The ARGUMENTS list defines the robot’s configurable parameters:

ARGUMENTS = [
    DeclareLaunchArgument('prefix', default_value='',
                          description='Prefix for robot joints and links'),
    DeclareLaunchArgument('add_world', default_value='true',
                          description='Whether to add world link'),
    # ... other arguments
]

These arguments allow users to customize the robot’s configuration without changing the code – like using command-line switches to modify a program’s behavior.

The generate_launch_description() function is where the magic happens. First, it sets up the file paths:

urdf_package = 'mycobot_description'
urdf_filename = 'mycobot_280.urdf.xacro'
rviz_config_filename = 'mycobot_280_description.rviz'

The robot’s description is loaded from a XACRO file (an XML macro file) and converted into a robot_description parameter:

robot_description_content = ParameterValue(Command([
    'xacro', ' ', urdf_model, ' ',
    'prefix:=', LaunchConfiguration('prefix'),
    # ... other parameters
]), value_type=str)

Then we create three key nodes:

1. Robot State Publisher:

start_robot_state_publisher_cmd = Node(
    package='robot_state_publisher',
    executable='robot_state_publisher',
    name='robot_state_publisher',
    output='screen',
    parameters=[{
        'use_sim_time': use_sim_time,
        'robot_description': robot_description_content}])

This node takes the robot description and joint states and publishes the 3D poses of all robot links – like a GPS system for each part of the robot.

2. Joint State Publisher (with optional GUI):

start_joint_state_publisher_cmd = Node(
    package='joint_state_publisher',
    executable='joint_state_publisher',
    name='joint_state_publisher',
    parameters=[{'use_sim_time': use_sim_time}],
    condition=UnlessCondition(jsp_gui))

This publishes joint positions – imagine it as the robot’s muscle control center. The GUI version allows manual control of these joints.

3. RViz:

start_rviz_cmd = Node(
    condition=IfCondition(use_rviz),
    package='rviz2',
    executable='rviz2',
    name='rviz2',
    output='screen',
    arguments=['-d', rviz_config_file])

This is our visualization tool, loading a pre-configured layout specified in the RViz config file.

Finally, everything is assembled into a LaunchDescription and returned:

ld = LaunchDescription(ARGUMENTS)
# Add all the actions...
return ld

This launch file structure is common in ROS 2 applications, providing a clean way to start multiple nodes simultaneously.

That’s it.

Keep building, and I will see you in the next tutorial!

Create and Visualize a Robotic Arm with URDF – ROS 2 Jazzy

In this tutorial, we will create a model of a robotic arm from scratch. By the end of this tutorial, you will be able to build this:

Our robotic arm model will be in the standard Unified Robot Description Format, also known as URDF. We will then visualize the robotic arm in RViz, a 3D visualization tool for ROS 2

This tutorial will follow a previous tutorial I created.

The official tutorial for creating a URDF file is here on the ROS 2 website; but that tutorial only deals with a fictitious robot.

It is far more fun and helpful to show you how to create a URDF file for a real-world robot, like the ones you will work with at your job or at school…like this one…a robotic arm made by Universal Robots that is making an omelette at the M Social Singapore Hotel: A robot made my omelette!

Within ROS 2, defining the URDF file of your robotic arm is important because it allows software tools to understand the robot’s structure, enabling tasks like simulation, motion planning, and sensor data interpretation. It is like giving the robot a digital body that software can interact with.

I will walk through all the steps below for creating the URDF for the myCobot 280 robotic arm by Elephant Robotics. Follow along with me click by click, keystroke by keystroke.  

Prerequisites

You can find all the code here on GitHub.

References for the myCobot 280 Robot

What is a URDF File?

A URDF (Universal Robot Description Format) file is an XML file that describes what a robot should look like in real life. It contains the complete physical description of the robot. Building the body of the robot is the first step when integrating your mobile robot or robotic arm with ROS 2.

The body of a robot consists of two components:

  1. Links
  2. Joints

Links are the rigid pieces of a robot. They are the “bones”. 

Links are connected to each other by joints. Joints are the pieces of the robot that move, enabling motion between connected links.

Consider the human arm below as an example. The shoulder, elbow, and wrist are joints. The upper arm, forearm and palm of the hand are links.

link_joint

For a robotic arm, links and joints look like this.

link-joint-robotic-arm

You can see that a robotic arm is made of rigid pieces (links) and non-rigid pieces (joints). Servo motors at the joints cause the links of a robotic arm to move.

For a mobile robot with LIDAR, links and joints look like this:

mobile-robot-joints-links

The wheel joints are revolute joints. Revolute joints cause rotational motion. The wheel joints in the photo connect the wheel link to the base link.

Fixed joints have no motion at all. You can see that the LIDAR is connected to the base of the robot via a fixed joint (i.e. this could be a simple screw that connects the LIDAR to the base of the robot).You can also have prismatic joints. The SCARA robot in this post has a prismatic joint. Prismatic joints cause linear motion between links (as opposed to rotational motion).

Create a Package

The first step is to create a ROS 2 package to store all your files.

Open a new terminal window, and create a new folder named mycobot_ros2.

cd ~/ros2_ws/src
mkdir mycobot_ros2
cd mycobot_ros2

Now create the package where we will store our URDF file.

ros2 pkg create --build-type ament_cmake --license BSD-3-Clause mycobot_description

Now, let’s create a metapackage.

I discuss the purpose of a metapackage in this post.

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. 

If you were to make your package available to install publicly using the apt-get package manager on Ubuntu for example, a metapackage would enable someone to automatically install all the ROS2 packages that are referenced in your metapackage. 

ros2 pkg create --build-type ament_cmake --license BSD-3-Clause mycobot_ros2
cd mycobot_ros2

Configure your package.xml file.

gedit package.xml

Make your package.xml file look like this:

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>mycobot_ros2</name>
  <version>0.0.0</version>
  <description>myCobot series robots by Elephant Robotics (metapackage).</description>
  <maintainer email="automaticaddison@todo.todo">ubuntu</maintainer>
  <license>BSD-3-Clause</license>

  <buildtool_depend>ament_cmake</buildtool_depend>
  
  <exec_depend>mycobot_description</exec_depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

Add a README.md to describe what the package is about.

cd ..
gedit README.md
# mycobot_ros2 #
![OS](https://img.shields.io/ubuntu/v/ubuntu-wallpapers/noble)
![ROS_2](https://img.shields.io/ros/v/jazzy/rclcpp)

I also recommend adding placeholder README.md files to the mycobot_ros2 folder.

# mycobot_ros2 #

The my_cobot_ros2 package is a metapackage. It contains lists of dependencies to other packages.

… as well as the mycobot_description folder.

# mycobot_description #

The mycobot_description package contains the robot description files that define the physical aspects of a robot, including its geometry, kinematics, dynamics, and visual aspects.

Now let’s build our new package:

cd ~/ros2_ws
colcon build

Let’s see if our new package is recognized by ROS 2.

Either open a new terminal window or source the bashrc file like this:

source ~/.bashrc
ros2 pkg list

You can see the newly created package of you scroll up to the “m” packages.

1-mycobot-package

Now let’s create the following folders:

mkdir -p ~/ros2_ws/src/mycobot_ros2/mycobot_description/meshes/mycobot_280/visual
mkdir -p ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/control
mkdir -p ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/mech
mkdir -p ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/sensors
mkdir -p ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/robots/

Add the Meshes

Mesh files are what make your robotic arm look realistic in robotics simulation and visualization programs.

Mesh files visually represent the 3D shape of the robot parts. These files are typically in formats such as STL (Stereo Lithography – .stl) or COLLADA (.dae).

The mesh files we are going to use were already available in the GitHub repository for Elephant Robotics, the manufacturers of the robotic arm we will be using in this tutorial. We didn’t have to create these files from scratch.

However, if you want to create your own custom 3D printed robotic arm in the future, for example, you can make your own mesh file. Here is how:

  1. Design the robot’s body using CAD programs like Onshape, Fusion 360, AutoCAD, or Solidworks. These tools help you create 3D models of the robot parts.
  2. 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.
  3. If needed, use a tool like Blender to simplify the mesh files. This makes them easier to use in simulations and visualizations.
  4. Add the simplified mesh files to your URDF file to visually represent what the robot looks like.

Let’s pull these mesh files off GitHub. 

First, open a new terminal window, and type:

cd ~/Downloads/

Clone the mycobot repository to your machine.

git clone -b jazzy https://github.com/automaticaddison/mycobot_ros2.git

Move to the mesh files for the robotic arm we are going to model:

cp -r mycobot_ros2/mycobot_description/meshes/* ~/ros2_ws/src/mycobot_ros2/mycobot_description/meshes/
ls ~/ros2_ws/src/mycobot_ros2/mycobot_description/meshes/mycobot_280/visual/

You can see the mesh files (.dae) and the corresponding .png files for the robotic arm.

2-see-mesh-files

Configure CMakeLists.txt

Let’s open Visual Studio Code.

cd ~/ros2_ws/
code .

Configure the CMakeLists.txt for the mycobot_description package. Make sure it looks like this:

cmake_minimum_required(VERSION 3.8)
project(mycobot_description)
 
# Check if the compiler being used is GNU's C++ compiler (g++) or Clang.
# Add compiler flags for all targets that will be defined later in the 
# CMakeLists file. These flags enable extra warnings to help catch
# potential issues in the code.
# Add options to the compilation process
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()
 
# Locate and configure packages required by the project.
find_package(ament_cmake REQUIRED)
find_package(urdf_tutorial REQUIRED)
 
# Copy necessary files to designated locations in the project
install (
  DIRECTORY meshes urdf
  DESTINATION share/${PROJECT_NAME}
)
 
# Automates the process of setting up linting for the package, which
# is the process of running tools that analyze the code for potential
# errors, style issues, and other discrepancies that do not adhere to
# specified coding standards or best practices.
if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()
 
ament_package()

Configure package.xml

Make sure your package.xml for the mycobot_description package looks like this:

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>mycobot_description</name>
  <version>0.0.0</version>
  <description>Contains the robot description files that define the physical
    aspects of a robot, including its geometry, kinematics, dynamics, and
    visual aspects.</description>
  <maintainer email="automaticaddison@todo.todo">ubuntu</maintainer>
  <license>BSD-3-Clause</license>

  <buildtool_depend>ament_cmake</buildtool_depend>
  <depend>urdf_tutorial</depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

Build the Package

Now let’s build the package.

cd ~/ros2_ws/
rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y

You will now see this in the terminal:

3-ros-distro-dependencies-check

Type your password, and press Enter to install.

Open a terminal window, and type:

build

If this command doesn’t work, type these commands:

echo "alias build='cd ~/dev_ws/ && colcon build && source ~/.bashrc'" >> ~/.bashrc
build

Create the URDF File

Now let’s create our URDF file. We will actually create it in XACRO format. I will use the terms URDF and XACRO interchangeably going forward.

XACRO files are like blueprints for URDF files, using macros and variables to simplify complex robot descriptions.

Imagine XACRO as the architect drawing up plans, and URDF as the final, ready-to-use construction document. Both file types represent the robotic arm, but XACRO offers more flexibility and organization.

Before a ROS tool or component can use the information in a XACRO file, it must first be processed (translated) into a URDF file. This step allows for the dynamic generation of robot descriptions based on the specific configurations defined in the XACRO file.

Open a terminal window, and type this command to create all the files we need. This is all a single command:

touch ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/mech/{g_shape_base_v2_0.urdf.xacro,adaptive_gripper.urdf.xacro,mycobot_280_arm.urdf.xacro} ~/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/robots/mycobot_280.urdf.xacro

Let’s start with creating our gripper: adaptive_gripper.urdf.xacro. Add this code.

Now let’s create the robot base: g_shape_base_v2_0.urdf.xacro. Add this code.

Now let’s create the robot arm: mycobot_280_arm.urdf.xacro. Add this code.

Now let’s create the full robot: mycobot_280.urdf.xacro. Add this code.

Understanding the URDF

Let’s walk through each file so we can understand what is going on.

adaptive_gripper.urdf.xacro

At the very start, we begin with our XML declaration and robot tag – this is standard for any URDF file. The xacro namespace tells us we’re using Xacro macros for more maintainable robot descriptions.

Looking at the first block of properties, these define the core characteristics of our gripper’s joints:

<xacro:property name="joint_effort" value="56.0"/>
<xacro:property name="joint_velocity" value="2.792527"/>
<xacro:property name="joint_damping" value="0.0"/>
<xacro:property name="joint_friction" value="0.0"/>

These values control how much force our joints can exert (effort), how fast they can move (velocity), and their friction/damping characteristics. Think of these as the physical limitations we’re putting on our gripper’s movements.

Next, we define some mass and inertial properties:

<xacro:property name="gripper_link_mass" value="0.007"/>
<xacro:property name="gripper_link_ixx" value="1e-6"/>
<xacro:property name="gripper_link_iyy" value="1e-6"/>
<xacro:property name="gripper_link_izz" value="1e-6"/>

These properties describe the mass of our gripper components and how their mass is distributed (inertia). These values are important for accurate physics simulation.

We then see a macro called gripper_link_inertial. This is a reusable template for inertial properties that we’ll use multiple times:

<xacro:macro name="gripper_link_inertial">
    <inertial>
      <origin xyz="0 0 0.0" rpy="0 0 0"/>
      <mass value="${gripper_link_mass}"/>
      <inertia ixx="${gripper_link_ixx}" ixy="0.0" ixz="0.0"
               iyy="${gripper_link_iyy}" iyz="0.0"
               izz="${gripper_link_izz}"/>
    </inertial>
</xacro:macro>

The main gripper definition starts with <xacro:macro name=”adaptive_gripper”>. This macro takes three parameters:

  • parent: what the gripper attaches to
  • prefix: a namespace prefix for unique naming
  • origin: where the gripper mounts

Looking at the links, we start with the gripper base. Each link has three main components:

<link name="${prefix}gripper_base">
    <inertial>...</inertial>    <!-- Physical properties -->
    <visual>...</visual>        <!-- How it looks -->
    <collision>...</collision>  <!-- Simplified shape for collision detection -->
</link>

The visual elements use mesh files (.dae format) for realistic appearance, while collision uses simple geometric shapes (boxes) for efficient collision checking.

Moving down, we see several joints. The key joint is gripper_controller, which is the main control point. Other joints are marked as “mimic” joints, meaning they follow the controller’s movement.

In the mimic element:

  • joint: The name of the joint to mimic.
  • multiplier: Scales the movement.
  • offset: Adds an offset to the movement.
   <joint name="${prefix}gripper_controller" type="revolute">
      <axis xyz="0 0 1"/>
      <limit effort="${joint_effort}" lower="-0.7" upper="0.15" velocity="${joint_velocity}"/>
      <parent link="${prefix}gripper_base"/>
      <child link="${prefix}gripper_left3"/>
      <origin xyz="-0.012 0.005 0" rpy="0 0 0"/>
      <dynamics damping="${joint_damping}" friction="${joint_friction}"/>
    </joint>

    <joint name="${prefix}gripper_base_to_${prefix}gripper_left2" type="revolute">
      <axis xyz="0 0 1"/>
      <limit effort="${joint_effort}" lower="-0.8" upper="0.5" velocity="${joint_velocity}"/>
      <parent link="${prefix}gripper_base"/>
      <child link="${prefix}gripper_left2"/>
      <origin xyz="-0.005 0.027 0" rpy="0 0 0"/>
      <mimic joint="${prefix}gripper_controller" multiplier="1.0" offset="0"/>
      <dynamics damping="${joint_damping}" friction="${joint_friction}"/>
    </joint>

The joint definitions include:

  • axis: which direction it rotates
  • limits: how far it can move
  • parent/child relationships: how parts connect
  • origin: where the joint is located relative to its parent

Finally, at the bottom, we have Gazebo-specific elements that define how the gripper appears in simulation:

<gazebo reference="${prefix}gripper_base">
    <visual>
        <material>...</material>
    </visual>
</gazebo>

The overall structure creates a gripper with six synchronized moving parts (three on each side) that can open and close to grasp objects. The gripper’s movement is controlled through a single main joint, with other joints following in a coordinated fashion.

g_shape_base_v2_0.urdf.xacro

Starting at the top, we have the standard XML declaration and robot tag with the xacro namespace. This is the same setup as our previous file.

The file defines a single macro called g_shape_base that takes two parameters:

  • base_link: The name of the base link
  • prefix: A namespace prefix for unique naming

Inside this macro, we define a single link with standard URDF components.

The inertial properties describe the physical characteristics.

  • origin: The position (xyz) and orientation (rpy: roll, pitch, yaw) of the link’s center of mass.
  • mass: The mass of the link in kilograms.
  • inertia: This describes how the mass is distributed, affecting how the link resists rotational motion.
<inertial>
    <origin xyz="0 0 0.0" rpy="0 0 0"/>  <!-- Center of mass at origin -->
    <mass value="0.33"/>                  <!-- Mass in kilograms -->
    <inertia                              <!-- Inertia matrix values -->
        ixx="0.000784" ixy="0.0" ixz="0.0"
        iyy="0.000867" iyz="0.0"
        izz="0.001598"/>
</inertial>

The visual component uses a mesh file for appearance. In this section, we specify how the link appears in simulations:

  • geometry: The shape of the link, defined here using a mesh file.
  • origin: The position and orientation of the visual representation.
<visual>
    <geometry>
        <mesh filename="file://$(find mycobot_description)/meshes/g_shape_base_v2_0/visual/base_link.dae"/>
    </geometry>
    <origin xyz="0.0 0 -0.03" rpy="0 0 ${pi/2}"/>  <!-- Offset and rotated 90 degrees -->
</visual>

The collision geometry uses a simple box shape for efficient collision detection:

  • geometry: Again, the shape, using the same mesh file.
  • origin: Position and orientation for collision purposes.
<collision>
    <geometry>
        <box size="0.105 0.14 0.02"/>  <!-- Box dimensions in meters -->
    </geometry>
    <origin xyz="0.0 0.0 -0.015" rpy="0 0 0"/>
</collision>

Finally, there’s a Gazebo-specific section that defines how the base appears in simulation, with gray coloring (0.5, 0.5, 0.5):

<gazebo reference="${prefix}${base_link}">
    <visual>
        <material>
            <ambient>0.5 0.5 0.5 1</ambient>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <specular>0.5 0.5 0.5 1</specular>
        </material>
    </visual>
</gazebo>

This file is much simpler than the gripper because it’s just describing a static base piece – there are no joints or moving parts. It’s essentially defining a gray platform that other robot components can be mounted to.

mycobot_280_arm.urdf.xacro

At the top, we start with our common joint properties. These will be used for all the moving joints in the arm:

<xacro:property name="joint_effort" value="56.0"/>      <!-- Maximum force the joint can exert -->
<xacro:property name="joint_velocity" value="2.792527"/> <!-- Maximum joint velocity -->
<xacro:property name="joint_damping" value="0.0"/>      <!-- Joint damping coefficient -->
<xacro:property name="joint_friction" value="0.0"/>     <!-- Joint friction coefficient →

Then we define the masses for each link in the arm:

<xacro:property name="link1_mass" value="0.12"/>
<xacro:property name="link2_mass" value="0.19"/>
<!-- ... and so on for links 3-6 and flange -->

The file includes two helpful macros to reduce code repetition:

  1. link_inertial: A template for defining inertial properties of links
  2. material_visual: A template for defining how links appear in Gazebo simulation

The main robot arm definition is in the mycobot_280_arm macro. This takes parameters for the base link name, flange link name, and a prefix for unique naming.

For each link (link1 through link6 plus the flange), we define:

<link name="${prefix}linkN">
    <inertial>...</inertial>    <!-- Physical properties using the link_inertial macro -->
    <visual>                    <!-- Visual appearance using mesh files -->
        <geometry>
            <mesh filename="..."/>
        </geometry>
    </visual>
    <collision>                 <!-- Simplified shapes for collision detection -->
        <geometry>
            <cylinder/> or <box/>
        </geometry>
    </collision>
</link>

The joints connecting these links are defined next. The first joint is fixed, while the others are revolute (rotating) joints:

  • name: The name of the joint.
  • type: The type of joint, which can be ‘fixed’, ‘revolute’, or others. A ‘fixed’ joint means no relative motion between the connected links.
  • parent and child: The links this joint connects.
  • origin: The position and orientation of the joint relative to the parent link.
<joint name="${prefix}linkN_to_${prefix}linkN+1" type="revolute">
    <axis xyz="0 0 1"/>         <!-- Rotation axis -->
    <limit effort="${joint_effort}" 
           lower="-2.879793" 
           upper="2.879793" 
           velocity="${joint_velocity}"/>  <!-- Motion limits -->
    <parent link="${prefix}linkN"/>       <!-- Which link it's attached to -->
    <child link="${prefix}linkN+1"/>      <!-- Which link it moves -->
    <origin xyz="x y z" rpy="r p y"/>     <!-- Position and orientation -->
</joint>

For revolute joints, we typically specify the following parameters:

  • axis: The axis of rotation.
    • 0 0 1 means we have rotation around the z axis of the parent coordinate frame.
  • limit: This parameter defines the motion limits, including:
    • effort: Maximum torque the joint can apply. Torque is the twisting force that makes something turn or rotate.
    • lower and upper: The range of allowed angles in radians.
    • velocity: Maximum angular velocity in radians per second.
  • damping: This parameter measured in Newton-meters per radian per second (N⋅m⋅s/rad), determines how much the joint resists moving at a certain speed, similar to how a shock absorber in a car slows down the movement of the wheels over bumps.

Finally, at the bottom, we set the visual properties for each link in Gazebo:

<xacro:material_visual ref_link="${prefix}link1" 
    ambient="0.5 0.5 0.5 1" 
    diffuse="0.5 0.5 0.5 1" 
    specular="0.5 0.5 0.5 1"/>

Most links are set to white (1 1 1), while the base and flange are gray (0.5 0.5 0.5).

This URDF describes a complete 6-axis robot arm with:

  • Realistic mass and inertial properties
  • Detailed 3D meshes for visualization
  • Simplified collision geometries for physics
  • Joint limits and dynamics
  • Consistent materials for simulation

mycobot_280.urdf.xacro

This file brings everything together.

At the top, we define several arguments that control how the robot is configured:
<xacro:arg name="add_world" default="true"/>      <!-- Whether to add a world link -->
<xacro:arg name="base_link" default="base_link"/> <!-- Name of the base link -->
<xacro:arg name="base_type" default="g_shape"/>   <!-- Type of base to use -->
<xacro:arg name="flange_link" default="link6_flange"/> <!-- Name of end flange -->
<xacro:arg name="gripper_type" default="adaptive_gripper"/> <!-- Type of gripper -->
<xacro:arg name="prefix" default=""/>        <!-- Prefix for naming -->
<xacro:arg name="use_gripper" default="true"/>    <!-- Whether to add a gripper -->

If add_world is true, we create a world link and connect our robot to it:

<xacro:if value="$(arg add_world)">
    <link name="world"/>
    <joint name="$(arg prefix)virtual_joint" type="fixed">
        <parent link="world"/>
        <child link="$(arg prefix)$(arg base_link)"/>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </joint>
</xacro:if>

Next, we handle the base:

<xacro:if value="${current_base == 'g_shape'}">
    <xacro:include filename="...g_shape_base_v2_0.urdf.xacro"/>
    <xacro:g_shape_base
        base_link="$(arg base_link)"
        prefix="$(arg prefix)"/>
</xacro:if>

Then we include and configure the main robot arm:

<xacro:include filename="...mycobot_280_arm.urdf.xacro"/>
<xacro:mycobot_280_arm
    base_link="$(arg base_link)"
    flange_link="$(arg flange_link)"
    prefix="$(arg prefix)">
    <origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:mycobot_280_arm>

Finally, if we want a gripper, we add it:

<xacro:if value="$(arg use_gripper)">
    <xacro:if value="${current_gripper == 'adaptive_gripper'}">
        <xacro:include filename="...adaptive_gripper.urdf.xacro"/>
        <xacro:adaptive_gripper
            parent="$(arg flange_link)"
            prefix="$(arg prefix)">
            <origin xyz="0 0 0.034" rpy="1.579 0 0"/>
        </xacro:adaptive_gripper>
    </xacro:if>
</xacro:if>

This file acts as the main assembly file, bringing together:

  • Optional world connection
  • The base
  • The 6-axis robot arm
  • Optional adaptive gripper

Each component is included as a separate file and configured using the arguments at the top. This modular approach makes it easy to swap out different bases or grippers, or create multiple robots with different configurations.

And that’s a detailed walkthrough of our XACRO file.

We’ve covered everything from declaring the robot model, defining links and joints, to setting up properties and mimics. 

XACRO files look complex the first time you see one. I remember the first time I looked at a XACRO file, and I got scared at how complicated it looked. Breaking them down into their components helps us understand how each part contributes to the robot’s functionality.

Build the Package

Now let’s build the package.

build

Visualize the URDF File

Let’s see the URDF file in RViz. 

Launch the URDF file. The conversion from XACRO to URDF happens behind the scenes. Be sure to have the correct path to your XACRO file.

ros2 launch urdf_tutorial display.launch.py model:=/home/ubuntu/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/robots/mycobot_280.urdf.xacro

By convention, the red axis is the x-axis, the green axis in the y-axis, and the blue axis is the z-axis.

4-display-robot-arm

Uncheck the TF checkbox to turn off the axes.

5-uncheck-tf

You can use the Joint State Publisher GUI pop-up window to move the links around.

6-joint-state-publisher-gui

On the left panel under Displays, play around by checking and unchecking different options.

For example, under Robot Model, you can see how the mass is distributed for the robot arm by unchecking “Visual Enabled” and “Collision Enabled” and checking the “Mass” checkbox under “Mass Properties”.

7-mass-checkbox

You can also see what simulation engines will use to detect collisions when the robotic arm is commanded to go to a certain point.

Uncheck “Visual Enabled” under Robot Model and check “Collision Enabled.”

8-collision-enabled
9-visual-and-collision-enabled-checked

You can also see the coordinate frames. 

Open a new terminal window, and type the following commands:

cd ~/Documents/
ros2 run tf2_tools view_frames

To see the coordinate frames, type:

dir
evince frames_YYYY-MM-DD_HH.MM.SS.pdf
10-coordinate-frames-arm

To close RViz, press CTRL + C.

So we can quickly visualize our robot in the future, let’s add a bash command that will enable us to quickly see our URDF.

echo "alias elephant='ros2 launch urdf_tutorial display.launch.py model:=/home/ubuntu/ros2_ws/src/mycobot_ros2/mycobot_description/urdf/robots/mycobot_280.urdf.xacro'" >> ~/.bashrc

To see it was added, type:

cat ~/.bashrc
build

Going forward, if you want to see your URDF file, type this command in the terminal window:

elephant

That’s it. Keep building, and I will see you in the next tutorial!