RobotLabs
  • Welcome
  • ESP32
    • PlatformIO
      • 1.1 Arduino Basics
      • 1.2 Install PlatformIO
      • 2.1 GPIO - LED Blink
      • 2.2 GPIO - LED Multi
      • 2.3 GPIO - LED Button
      • 3.1 PWM - LED Fade
      • 3.2 ADC - Analog Input
      • 4.1 IIC - OLED
    • MicroPython
    • ESP32 Projects
  • ROS
    • ROS2 Jazzy
      • 1.1 Install ROS 2 Jazzy
      • 1.2 Install VS Code
      • 1.3 Save ROS code on GitHub
      • 2.1 Create a Mobile Robot with URDF and Visualize it
      • 2.3 Create Launch Files to Display the URDF in RViz
      • 2.4 Simulation with Gazebo
      • 2.5 Gazebo sensors
      • 2.6 Sensor fusion and SLAM
    • MoveIt2
      • Moveit 2 joint position control with keyboard
      • Moveit2 joint velocity control for Panda robot arm
    • Perception
      • PCL-ROS
  • FOC
    • SimpleFOC
      • Install simpleFOC Lib
  • Template
    • Markdown
    • Interactive blocks
    • OpenAPI
    • Integrations
Powered by GitBook
On this page
  • Add RViz Configuration File
  • Launch file based on urdf-tutorial
  • Create another Launch File
  • Edit CMakeLists.txt
  • Build the Package
  • Launch the Launch Files
  • Launch File Explanation
  1. ROS
  2. ROS2 Jazzy

2.3 Create Launch Files to Display the URDF in RViz

Previous2.1 Create a Mobile Robot with URDF and Visualize itNext2.4 Simulation with Gazebo

Last updated 3 months ago

In our last tutorial, we launch the URDF file based on urdf-tutorial package as follows:

sudo apt install ros-jazzy-urdf-tutorial
ros2 launch urdf_tutorial display.launch.py model:=/home/robotlabs/ros2_ws/src/mec_mobile/mec_mobile_description/urdf/robots/robot_3d.urdf.xacro

Now, let's create our own launch file and load our own .rviz file as well.

Add RViz Configuration File

Although is possible to use RViz with command like this, it's not the most convenient way, as we can move all these tasks into a ROS launch file with loading a .rviz file. Let's add the RViz configuration file first and then use it in our launch file.

cd ~/ros2_ws/src/mec_mobile/mec_mobile_description/ 
mkdir rviz && cd rviz

Create a file inside rviz folder and name it with mec_mobile_description.rviz

mec_mobile_description.rviz
Panels:
  - Class: rviz_common/Displays
    Name: Displays
  - Class: rviz_common/Views
    Name: Views
Visualization Manager:
  Displays:
    - Class: rviz_default_plugins/Grid
      Name: Grid
      Value: true
    - Alpha: 0.8
      Class: rviz_default_plugins/RobotModel
      Description Topic:
        Value: /robot_description
      Name: RobotModel
      Value: true
    - Class: rviz_default_plugins/TF
      Name: TF
      Value: true
  Global Options:
    Fixed Frame: base_link
  Tools:
    - Class: rviz_default_plugins/MoveCamera
  Value: true
  Views:
    Current:
      Class: rviz_default_plugins/Orbit
      Distance: 1.7
      Name: Current View
      Pitch: 0.33
      Value: Orbit (rviz)
      Yaw: 5.5
Window Geometry:
  Height: 800
  Width: 1200

Note that we don't need to understand all the details of this configuration file. It can be generated automatically through RViz.

The RViz configuration files set up an RViz with a grid, a robot model, and coordinate frame visualizations etc. It 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.

Launch file based on urdf-tutorial

Let's create the check_urdf.launch.py file in the launch folder inside mec_mobile_description:

cd ~/ros2_ws/src/mec_mobile/mec_mobile_description/ 
mkdir launch && cd launch
check_urdf.launch.py
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
    
    # Set urdf package path, replace it with your package
    pkg_urdf_path = FindPackageShare('mec_mobile_description')
    default_rviz_config_path = PathJoinSubstitution([pkg_urdf_path, 'rviz', 'mec_mobile_description.rviz'])

    # Show joint state publisher GUI for joints
    gui_arg = DeclareLaunchArgument(name='gui', default_value='true', choices=['true', 'false'],
                                    description='Flag to enable joint_state_publisher_gui')
    
    # RViz config file path
    rviz_arg = DeclareLaunchArgument(name='rvizconfig', default_value=default_rviz_config_path,
                                    description='Absolute path to rviz config file')
    

    # URDF model path within your package
    model_arg = DeclareLaunchArgument(
        'model', default_value='robot_3d.urdf.xacro',
        description='Name of the URDF description to load'
    )

    # Use built-in ROS2 URDF launch package with our own arguments
    urdf = IncludeLaunchDescription(
        PathJoinSubstitution([FindPackageShare('urdf_launch'), 'launch', 'display.launch.py']),
        launch_arguments={
            'urdf_package': 'mec_mobile_description',
            'urdf_package_path': PathJoinSubstitution(['urdf','robots', LaunchConfiguration('model')]),
            'rviz_config': LaunchConfiguration('rvizconfig'),
            'jsp_gui': LaunchConfiguration('gui')}.items()
    )

    launchDescriptionObject = LaunchDescription()

    launchDescriptionObject.add_action(gui_arg)
    launchDescriptionObject.add_action(rviz_arg)
    launchDescriptionObject.add_action(model_arg)
    launchDescriptionObject.add_action(urdf)

    return launchDescriptionObject

This launch file is very useful to visualize our URDF during development. Now add the launch to the CMakeLists.txt file and build the workspace to try it:

ros2 launch mec_mobile_description check_urdf.launch.py 

Create another Launch File

Open a terminal window, and move to the mobile robot directory.

cd ~/ros2_ws/src/mec_mobile/mec_mobile_description/ 
mkdir launch && cd launch

Add a file with VS Code in the launch folder named robot_state_publisher.launch.py (with robot state and joint state publisher nodes more than the previous check_urdf.launch.py):

robot_state_publisher.launch.py
# This file launches the robot state publisher, joint state publisher,
# and RViz2 for visualizing the 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 = 'mec_mobile_description'
    urdf_filename = 'robot_3d.urdf.xacro'
    rviz_config_filename = 'mec_mobile_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',
        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

Edit CMakeLists.txt

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

cd ~/ros2_ws/src/mec_mobile/mec_mobile_description/ 

Add following code with VS Code to CMakeLists.txt:

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

Build the Package

Now let’s build the package.

cd ~/ros2_ws
colcon build

Launch the Launch Files

Launch your launch files:

ros2 launch mec_mobile_description robot_state_publisher.launch.py

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

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

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

ros2 launch mec_mobile_description robot_state_publisher.launch.py jsp_gui:=false use_rviz:=false

Note: The ARGUMENTS in launch.py defines the robot’s configurable parameters.

Launch File Explanation

robot_state_publisher.launch.py

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 to arrange multiple nodes:

  • 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 = 'mec_mobile_description'
urdf_filename = 'robot_3d.urdf.xacro'
rviz_config_filename = 'mec_mobile_description.rviz'

The robot’s description is loaded from a XACRO file (an XML macro file) and converted into a robot_description_content 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:

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

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}])

2. Joint State Publisher (with optional GUI):

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

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))

3. RViz:

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

start_rviz_cmd = Node(
    condition=IfCondition(use_rviz),
    package='rviz2',
    executable='rviz2',
    name='rviz2',
    output='screen',
    arguments=['-d', 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 all.

ROS provides several tools to visualize various data like rqt and RViz. We can start the RViz with the rviz2 command, then we can add the Robot Model view, browse for our URDF file and type base_link as Fixed Frame etc.

The source of urdf-tutorial package is . This package does exactly what we need, but it's not good to build up our tools onto it, so we can create our own launch file based on this package.

We can also create a custom launch file to launch a mobile robot in RViz as . Launch files in ROS2 allows you to start multiple nodes and set parameters with a single command.

here
ros2 official docs