How to Load a URDF File into Gazebo – ROS 2

In this post, I will show you how to load a URDF file into Gazebo. Universal Robot Description Format (URDF) is the standard ROS format for robot modeling. 

If you would like to learn more about URDF files, check out this page.

Prerequisites

You can find the files for this post here on my Google Drive.

Create the URDF File

I am going to open up a terminal window, and type the following command to go to the directory where my URDF file will be located.

cd ~/dev_ws/src/two_wheeled_robot/urdf

Add your URDF file to this folder. For example, you can add a URDF file like this:

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

  <!-- ****************** ROBOT CONSTANTS *******************************  -->
  <!-- Define the size of the robot's main chassis in meters -->
  <xacro:property name="base_width" value="0.39"/>
  <xacro:property name="base_length" value="0.70"/>
  <xacro:property name="base_height" value="0.20"/>
	
  <!-- Define the shape of the robot's two back wheels in meters -->
  <xacro:property name="wheel_radius" value="0.14"/>
  <xacro:property name="wheel_width" value="0.06"/>

  <!-- x-axis points forward, y-axis points to left, z-axis points upwards -->
  <!-- Define the gap between the wheel and chassis along y-axis in meters -->
  <xacro:property name="wheel_ygap" value="0.035"/>

  <!-- Position the wheels along the z-axis -->
  <xacro:property name="wheel_zoff" value="0.05"/>

  <!-- Position the wheels along the x-axis -->
  <xacro:property name="wheel_xoff" value="0.221"/>

  <!-- Position the caster wheel along the x-axis -->
  <xacro:property name="caster_xoff" value="0.217"/>

  <!-- Define intertial property macros  -->
  <xacro:macro name="box_inertia" params="m w h d">
    <inertial>
      <origin xyz="0 0 0" rpy="${pi/2} 0 ${pi/2}"/>
      <mass value="${m}"/>
      <inertia ixx="${(m/12) * (h*h + d*d)}" ixy="0.0" ixz="0.0" iyy="${(m/12) * (w*w + d*d)}" iyz="0.0" izz="${(m/12) * (w*w + h*h)}"/>
    </inertial>
  </xacro:macro>

  <xacro:macro name="cylinder_inertia" params="m r h">
    <inertial>
      <origin xyz="0 0 0" rpy="${pi/2} 0 0" />
      <mass value="${m}"/>
      <inertia ixx="${(m/12) * (3*r*r + h*h)}" ixy = "0" ixz = "0" iyy="${(m/12) * (3*r*r + h*h)}" iyz = "0" izz="${(m/2) * (r*r)}"/>
    </inertial>
  </xacro:macro>

  <xacro:macro name="sphere_inertia" params="m r">
    <inertial>
      <mass value="${m}"/>
      <inertia ixx="${(2/5) * m * (r*r)}" ixy="0.0" ixz="0.0" iyy="${(2/5) * m * (r*r)}" iyz="0.0" izz="${(2/5) * m * (r*r)}"/>
    </inertial>
  </xacro:macro>
  
  <!-- ********************** ROBOT BASE *********************************  -->
  <link name="base_link">
    <visual>
      <origin xyz="0 0 -0.05" rpy="1.5707963267949 0 3.141592654"/>
      <geometry>
        <mesh filename="file://$(find two_wheeled_robot)/meshes/robot_base.stl" />
      </geometry>
      <material name="Red">
        <color rgba="1.0 0.0 0.0 1.0"/>
      </material>
    </visual>

    <collision>
      <geometry>
        <box size="${base_length} ${base_width} ${base_height}"/>
      </geometry>
    </collision>

    <xacro:box_inertia m="15.0" w="${base_width}" d="${base_length}" h="${base_height}"/>
  </link>

  <gazebo reference="base_link">
    <material>Gazebo/Red</material>
  </gazebo>

  
  <!-- ****************** ROBOT BASE FOOTPRINT ***************************  -->
  <!-- Define the center of the main robot chassis projected on the ground -->	
  <link name="base_footprint">
  	<xacro:box_inertia m="0" w="0" d="0" h="0"/>
  </link>

  <!-- The base footprint of the robot is located underneath the chassis -->
  <joint name="base_joint" type="fixed">
    <parent link="base_link"/>
    <child link="base_footprint"/>
    <origin xyz="0.0 0.0 ${-(wheel_radius+wheel_zoff)}" rpy="0 0 0"/>
  </joint>

  <!-- *********************** DRIVE WHEELS ******************************  -->
  <xacro:macro name="wheel" params="prefix x_reflect y_reflect">
    <link name="${prefix}_link">
      <visual>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
        <geometry>
            <cylinder radius="${wheel_radius}" length="${wheel_width}"/>
        </geometry>
        <material name="Gray">
          <color rgba="0.5 0.5 0.5 1.0"/>
        </material>
      </visual>

      <collision>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/> 
        <geometry>
          <cylinder radius="${wheel_radius}" length="${wheel_width}"/>
        </geometry>
      </collision>

      <xacro:cylinder_inertia m="0.5" r="${wheel_radius}" h="${wheel_width}"/>
    </link>

    <!-- Connect the wheels to the base_link at the appropriate location, and 
         define a continuous joint to allow the wheels to freely rotate about
         an axis -->
    <joint name="${prefix}_joint" type="continuous">
      <parent link="base_link"/>
      <child link="${prefix}_link"/>
      <origin xyz="${x_reflect*wheel_xoff} ${y_reflect*(base_width/2+wheel_ygap)} ${-wheel_zoff}" rpy="0 0 0"/>
      <axis xyz="0 1 0"/>
    </joint>
  </xacro:macro>

  <!-- Instantiate two wheels using the macro we just made through the 
       xacro:wheel tags. We also define the parameters to have one wheel
       on both sides at the back of our robot (i.e. x_reflect=-1). -->
  <xacro:wheel prefix="drivewhl_l" x_reflect="-1" y_reflect="1" />
  <xacro:wheel prefix="drivewhl_r" x_reflect="-1" y_reflect="-1" />

  <!-- *********************** CASTER WHEEL ******************************  -->
  <!-- We add a caster wheel. It will be modeled as sphere.
       We define the wheel’s geometry, material and the joint to connect it to 
       base_link at the appropriate location. -->
  <link name="front_caster">
    <visual>
      <geometry>
        <sphere radius="${(wheel_radius+wheel_zoff-(base_height/2))}"/>
      </geometry>
      <material name="Cyan">
        <color rgba="0 1.0 1.0 1.0"/>
      </material>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <sphere radius="${(wheel_radius+wheel_zoff-(base_height/2))}"/>
      </geometry>
    </collision>

    <xacro:sphere_inertia m="0.5" r="${(wheel_radius+wheel_zoff-(base_height/2))}"/>
  </link>
  
  <gazebo reference="front_caster">
    <mu1>0.01</mu1>
    <mu2>0.01</mu2>
    <material>Gazebo/White</material>
  </gazebo>

  <joint name="caster_joint" type="fixed">
    <parent link="base_link"/>
    <child link="front_caster"/>
    <origin xyz="${caster_xoff} 0.0 ${-(base_height/2)}" rpy="0 0 0"/>
  </joint>

  <!-- *********************** IMU SETUP *********************************  -->
  <!-- Each sensor must be attached to a link.                              --> 
  <link name="imu_link">
    <visual>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
    </visual>
    
    <collision>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
    </collision>
      
    <xacro:box_inertia m="0.1" w="0.1" d="0.1" h="0.1"/>
  </link>
    
  <joint name="imu_joint" type="fixed">
    <parent link="base_link"/>
    <child link="imu_link"/>
    <origin xyz="0 0 0.01"/>
  </joint>
    
  <gazebo reference="imu_link">
    <gravity>true</gravity>
    <sensor name="twr_imu" type="imu">
      <always_on>true</always_on>
      <update_rate>100</update_rate>
      <visualize>true</visualize>
      <imu>
        <orientation>
          <x>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>2e-3</stddev>
            </noise>
          </x>
          <y>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>2e-3</stddev>
            </noise>
          </y>
          <z>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>2e-3</stddev>
            </noise>
          </z>
        </orientation>
        <angular_velocity>
          <x>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>2e-4</stddev>
            </noise>
          </x>
          <y>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>2e-4</stddev>
            </noise>
          </y>
          <z>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>2e-4</stddev>
            </noise>
          </z>
        </angular_velocity>
        <linear_acceleration>
          <x>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>1.7e-2</stddev>
            </noise>
          </x>
          <y>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>1.7e-2</stddev>
            </noise>
          </y>
          <z>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>1.7e-2</stddev>
            </noise>
          </z>
        </linear_acceleration>
      </imu>
      <plugin name="two_wheeled_robot_imu" filename="libgazebo_ros_imu_sensor.so">
        <initial_orientation_as_reference>false</initial_orientation_as_reference>
        <frame_name>imu_link</frame_name>
        <ros>
          <namespace>/imu</namespace>
          <remapping>~/out:=data</remapping>
        </ros>
      </plugin>
    </sensor>
</gazebo>

  <!-- *********************** LIDAR SETUP **********************************  -->
 <link name="lidar_link">
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="0.125"/>
      <inertia ixx="0.001"  ixy="0"  ixz="0" iyy="0.001" iyz="0" izz="0.001" />
    </inertial>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
         <cylinder radius="0.0508" length="0.75"/>
      </geometry>
    </collision>

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
         <cylinder radius="0.0508" length="0.75"/>
      </geometry>
    </visual>
  </link>
    
  <joint name="lidar_joint" type="fixed">
    <parent link="base_link"/>
    <child link="lidar_link"/>
    <origin xyz="0.215 0.0 0.30" rpy="0 0 0"/>
  </joint>
    
  <gazebo reference="lidar_link">
    <sensor name="lidar" type="ray">
      <always_on>true</always_on>
      <visualize>true</visualize>
      <update_rate>5</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>120</samples>
            <resolution>1.000000</resolution>
            <min_angle>-3.14159</min_angle>
            <max_angle>3.14159</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.3</min>
          <max>15.0</max>
          <resolution>0.015</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
      </ray>
      <plugin name="scan" filename="libgazebo_ros_ray_sensor.so">
        <ros>
          <remapping>~/out:=scan</remapping>
        </ros>
        <output_type>sensor_msgs/LaserScan</output_type>
        <frame_name>lidar_link</frame_name>
      </plugin>
    </sensor>
  </gazebo>
  <gazebo reference="lidar_link">
    <mu1>0.01</mu1>
    <mu2>0.01</mu2>
    <material>Gazebo/Black</material>
  </gazebo>


 <!-- *********************** WHEEL ODOMETRY ***************************    --> 
  <gazebo>
    <plugin name="two_wheeled_robot_diff_drive" filename="libgazebo_ros_diff_drive.so">

      <update_rate>30</update_rate>
     
      <!-- wheels -->
      <left_joint>drivewhl_l_joint</left_joint>
      <right_joint>drivewhl_r_joint</right_joint>

      <!-- kinematics -->
      <wheel_separation>0.52</wheel_separation>
      <wheel_diameter>0.28</wheel_diameter>

      <!-- limits -->
      <max_wheel_torque>20</max_wheel_torque>
      <max_wheel_acceleration>1.0</max_wheel_acceleration>

      <!-- Receive velocity commands on this ROS topic -->
      <command_topic>cmd_vel</command_topic>

      <!-- output -->
      <!-- When false, publish no wheel odometry data to a ROS topic -->
      <publish_odom>true</publish_odom>

      <!-- When true, publish coordinate transform from odom to base_footprint -->
      <!-- I usually use the robot_localization package to publish this transform -->   
      <publish_odom_tf>false</publish_odom_tf>
    
      <!-- When true, publish coordinate transform from base_link to the wheels -->
      <!-- The robot_state_publisher package is often used to publish this transform -->   
      <publish_wheel_tf>true</publish_wheel_tf>

      <odometry_topic>odom</odometry_topic>
      <odometry_frame>odom</odometry_frame>
      <robot_base_frame>base_link</robot_base_frame>

      <odometry_source>1</odometry_source>
      <ros>
        <remapping>odom:=wheel/odometry</remapping>
      </ros>
    </plugin>
  </gazebo>
</robot>

Create the Launch File

Now we want to create a launch file.

I am going to go to my launch folder and create the file. Here is the command I will type in my terminal window.

cd ~/dev_ws/src/two_wheeled_robot/launch
gedit launch_urdf_into_gazebo.launch.py

Type the following code inside the file.

# Author: Addison Sears-Collins
# Date: September 23, 2021
# Description: Load a URDF and world file into Gazebo.
# https://automaticaddison.com

import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription
from launch.conditions import IfCondition, UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import Command, LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():

  # Constants for paths to different files and folders
  gazebo_models_path = 'models'
  package_name = 'two_wheeled_robot'
  robot_name_in_model = 'two_wheeled_robot'
  rviz_config_file_path = 'rviz/urdf_gazebo_config.rviz'
  urdf_file_path = 'urdf/two_wheeled_robot_nav2.urdf'
  world_file_path = 'worlds/neighborhood.world'
    
  # Pose where we want to spawn the robot
  spawn_x_val = '0.0'
  spawn_y_val = '0.0'
  spawn_z_val = '0.0'
  spawn_yaw_val = '0.00'

  ############ You do not need to change anything below this line #############
  
  # Set the path to different files and folders.  
  pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros')   
  pkg_share = FindPackageShare(package=package_name).find(package_name)
  default_urdf_model_path = os.path.join(pkg_share, urdf_file_path)
  default_rviz_config_path = os.path.join(pkg_share, rviz_config_file_path)
  world_path = os.path.join(pkg_share, world_file_path)
  gazebo_models_path = os.path.join(pkg_share, gazebo_models_path)
  os.environ["GAZEBO_MODEL_PATH"] = gazebo_models_path
  
  # Launch configuration variables specific to simulation
  gui = LaunchConfiguration('gui')
  headless = LaunchConfiguration('headless')
  namespace = LaunchConfiguration('namespace')
  rviz_config_file = LaunchConfiguration('rviz_config_file')
  urdf_model = LaunchConfiguration('urdf_model')
  use_namespace = LaunchConfiguration('use_namespace')
  use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
  use_rviz = LaunchConfiguration('use_rviz')
  use_sim_time = LaunchConfiguration('use_sim_time')
  use_simulator = LaunchConfiguration('use_simulator')
  world = LaunchConfiguration('world')
  
  # Declare the launch arguments  
  declare_use_joint_state_publisher_cmd = DeclareLaunchArgument(
    name='gui',
    default_value='True',
    description='Flag to enable joint_state_publisher_gui')
    
  declare_namespace_cmd = DeclareLaunchArgument(
    name='namespace',
    default_value='',
    description='Top-level namespace')

  declare_use_namespace_cmd = DeclareLaunchArgument(
    name='use_namespace',
    default_value='false',
    description='Whether to apply a namespace to the navigation stack')
            
  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_simulator_cmd = DeclareLaunchArgument(
    name='headless',
    default_value='False',
    description='Whether to execute gzclient')

  declare_urdf_model_path_cmd = DeclareLaunchArgument(
    name='urdf_model', 
    default_value=default_urdf_model_path, 
    description='Absolute path to robot urdf file')
    
  declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
    name='use_robot_state_pub',
    default_value='True',
    description='Whether to start the robot state publisher')

  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='true',
    description='Use simulation (Gazebo) clock if true')

  declare_use_simulator_cmd = DeclareLaunchArgument(
    name='use_simulator',
    default_value='True',
    description='Whether to start the simulator')

  declare_world_cmd = DeclareLaunchArgument(
    name='world',
    default_value=world_path,
    description='Full path to the world model file to load')
  
  # 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',
    parameters=[{'robot_description': Command(['xacro ', urdf_model])}])

  # Publish the joint states of the robot
  start_joint_state_publisher_cmd = Node(
    package='joint_state_publisher',
    executable='joint_state_publisher',
    name='joint_state_publisher',
    condition=UnlessCondition(gui))

  # Launch RViz
  start_rviz_cmd = Node(
    package='rviz2',
    executable='rviz2',
    name='rviz2',
    output='screen',
    arguments=['-d', rviz_config_file])

  # Start Gazebo server
  start_gazebo_server_cmd = IncludeLaunchDescription(
    PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
    condition=IfCondition(use_simulator),
    launch_arguments={'world': world}.items())

  # Start Gazebo client    
  start_gazebo_client_cmd = IncludeLaunchDescription(
    PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')),
    condition=IfCondition(PythonExpression([use_simulator, ' and not ', headless])))

  # Launch the robot
  spawn_entity_cmd = Node(
    package='gazebo_ros', 
    executable='spawn_entity.py',
    arguments=['-entity', robot_name_in_model, 
                '-topic', 'robot_description',
                    '-x', spawn_x_val,
                    '-y', spawn_y_val,
                    '-z', spawn_z_val,
                    '-Y', spawn_yaw_val],
                    output='screen')

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

  # Declare the launch options
  ld.add_action(declare_use_joint_state_publisher_cmd)
  ld.add_action(declare_namespace_cmd)
  ld.add_action(declare_use_namespace_cmd)
  ld.add_action(declare_rviz_config_file_cmd)
  ld.add_action(declare_simulator_cmd)
  ld.add_action(declare_urdf_model_path_cmd)
  ld.add_action(declare_use_robot_state_pub_cmd)  
  ld.add_action(declare_use_rviz_cmd) 
  ld.add_action(declare_use_sim_time_cmd)
  ld.add_action(declare_use_simulator_cmd)
  ld.add_action(declare_world_cmd)

  # Add any actions
  ld.add_action(start_gazebo_server_cmd)
  ld.add_action(start_gazebo_client_cmd)
  ld.add_action(spawn_entity_cmd)
  ld.add_action(start_robot_state_publisher_cmd)
  ld.add_action(start_joint_state_publisher_cmd)
  ld.add_action(start_rviz_cmd)

  return ld

Save the file and close it.

Build the Package

Go to the root folder.

cd ~/dev_ws/

Build the package.

colcon build

Launch the Launch File

Now let’s launch the launch file.

cd ~/dev_ws/
ros2 launch two_wheeled_robot launch_urdf_into_gazebo.launch.py

Here is the output:

1-load-urdf-into-gazebo-1

You will also see that an Rviz window pops up. You can change the Fixed Frame to base_link so the robot appears.

2-fixed-frame-base-link
3-robot-base-link

That’s it. Keep building!

Useful World Files for Gazebo and ROS 2 Simulations

In this post, I will show you some useful world files that you can use in your ROS 2/Gazebo robotics development work. 

All of these world files have been tested on my machine.

A lot of these world files were originally missing key models and other mesh files when I downloaded them from GitHub and loaded them on my machine…so I spent several (at times, frustrating) days fixing those issues to save you a lot of headache.

Prerequisites

Link to the World and Models Files

You can find the files for all worlds and models (which are the objects inside those worlds) here on my Google Drive. Check the ‘worlds’ and ‘models’ folder of my two_wheeled_robot package.

Useful Command

To switch between world files when you are loading a world into Gazebo using a ROS 2 launch file, you can use the following command (all this command goes on one line):

ros2 launch <package_name> <launch_file_name.py> world:=<path_to_world_file>

For example:

ros2 launch two_wheeled_robot load_world_into_gazebo.launch.py world:=~/dev_ws/src/two_wheeled_robot_worlds/cafe.world

ROS 2 Launch File

Here is what my launch file looks like:

# Author: Addison Sears-Collins
# Date: September 23, 2021
# Description: Load a world file into Gazebo.
# https://automaticaddison.com

import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.conditions import IfCondition, UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import Command, LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

def generate_launch_description():

  # Set the path to the Gazebo ROS package
  pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros')   
  
  # Set the path to this package.
  pkg_share = FindPackageShare(package='two_wheeled_robot').find('two_wheeled_robot')

  # Set the path to the world file
  world_file_name = 'warehouse.world'
  world_path = os.path.join(pkg_share, 'worlds', world_file_name)
  
  # Set the path to the SDF model files.
  gazebo_models_path = os.path.join(pkg_share, 'models')
  os.environ["GAZEBO_MODEL_PATH"] = gazebo_models_path

  ########### YOU DO NOT NEED TO CHANGE ANYTHING BELOW THIS LINE ##############  
  # Launch configuration variables specific to simulation
  headless = LaunchConfiguration('headless')
  use_sim_time = LaunchConfiguration('use_sim_time')
  use_simulator = LaunchConfiguration('use_simulator')
  world = LaunchConfiguration('world')

  declare_simulator_cmd = DeclareLaunchArgument(
    name='headless',
    default_value='False',
    description='Whether to execute gzclient')
    
  declare_use_sim_time_cmd = DeclareLaunchArgument(
    name='use_sim_time',
    default_value='true',
    description='Use simulation (Gazebo) clock if true')

  declare_use_simulator_cmd = DeclareLaunchArgument(
    name='use_simulator',
    default_value='True',
    description='Whether to start the simulator')

  declare_world_cmd = DeclareLaunchArgument(
    name='world',
    default_value=world_path,
    description='Full path to the world model file to load')
   
  # Specify the actions
  
  # Start Gazebo server
  start_gazebo_server_cmd = IncludeLaunchDescription(
    PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
    condition=IfCondition(use_simulator),
    launch_arguments={'world': world}.items())

  # Start Gazebo client    
  start_gazebo_client_cmd = IncludeLaunchDescription(
    PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')),
    condition=IfCondition(PythonExpression([use_simulator, ' and not ', headless])))

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

  # Declare the launch options
  ld.add_action(declare_simulator_cmd)
  ld.add_action(declare_use_sim_time_cmd)
  ld.add_action(declare_use_simulator_cmd)
  ld.add_action(declare_world_cmd)

  # Add any actions
  ld.add_action(start_gazebo_server_cmd)
  ld.add_action(start_gazebo_client_cmd)

  return ld

Worlds

Cafe World

I showed you how to load the cafe.world file in this post. Here are the files for that. You can use this world to test an indoor delivery robot that can deliver food and drinks to a table.

5-cafe-world-1

Car World

Let’s build a world for a car to move around in. Credit to this GitHub repository for the model and world files. You can use this world to test autonomous vehicle algorithms.

Here is how it looks:

car-world-1
car-world-2

Distribution Center World

Let’s create a distribution center world. Credit to this GitHub repository for the model and world files. You can use this world to test autonomous mobile robots.

Here is how it looks:

distribution-center-world

Factory World

Let’s create a factory world. Credit to this GitHub repository for the model and world files. You can use this world to test autonomous mobile robots.

Here is how it looks:

factory-world

Farm World

Let’s create a farm world. Credit to this GitHub repository for the model files. You can use this world to test autonomous weeding machines or tractors for agricultural robotics work.

Here is how it looks:

farm-world
farm-world-2

Hospital World

Let’s create a hospital world. Credit to this GitHub repository for the model and world files. You can use these worlds to test indoor delivery robots or mobile disinfection robots.

Here is how it looks:

hospital-world

Here is how it looks with two floors:

hospital-2-floors
hospital-world-2

Here is how it looks with three floors:

hospital-world-3-floors

House World

Let’s create a hospital world. Credit to this GitHub repository for the model and world files. You can use this world to test autonomous vacuum cleaners or other household robots.

Here is how it looks:

house-world

Inventory World

Let’s create an inventory world. You can use this world to create QR scanning drones that can perform inventory management in a warehouse. Credit to this GitHub repository for the model and world files.

Here is how it looks:

inventory-world

Lawn World

Here is what my lawn world looks like. You could use this simulated world to test autonomous lawnmower algorithms.

lawn-world

Neighborhood World

Let’s create a neighborhood world. Credit to this GitHub repository for the world file. You can use this world to test outdoor delivery robots.

Here is how it looks:

neighborhood-world

Office World

Let’s create an office world. Credit to this GitHub repository for the world file. You can use this world to test indoor delivery robots.

Go to your media folder of Gazebo.

cd /usr/share/gazebo-11/media

Make a meshes folder.

sudo mkdir meshes

Add these meshes to the folder. The command below goes all on one line inside the Linux terminal.

sudo cp ~/dev_ws/src/two_wheeled_robot/meshes/office/* /usr/share/gazebo-11/media/meshes

Now copy the media files (both the scripts and textures).

sudo cp ~/dev_ws/src/two_wheeled_robot/media/materials/scripts/* /usr/share/gazebo-11/media/materials/scripts
sudo cp ~/dev_ws/src/two_wheeled_robot/media/materials/textures/* /usr/share/gazebo-11/media/materials/textures

Make sure your models folder has all these models.

Add the office.world file to your worlds folder.

Modify the launch file and launch the world.

Here is how the world looks:

office-world
office-world-2

Warehouse World

Let’s create a warehouse world. Credit to this GitHub repository for the model and world files. You can use this world to test autonomous mobile robots that move pallets and shelves around the warehouse floor.

Here is how it looks:

warehouse-world
warehouse-world-2

That’s it. Keep building!

How to Load a World File into Gazebo – ROS 2

In this tutorial, I will show you how to load a .world file into Gazebo. 

You can learn all about world files at this link.

Real-World Applications

Simulating a world has a number of real-world robotic applications: 

  • Ground Delivery
  • Hospitals and Medical Centers
  • Hotels (Room Service)
  • Offices
  • Restaurants
  • Warehouses
  • And more…

Roboticists like to simulate robots in simulated worlds in order to test out different algorithms. You can imagine the cost of making mistakes with a physical robot can be high (e.g. crashing a mobile robot into a wall at high speed means lost money).

You can get all the code for this tutorial here.

Let’s get started!

Prerequisites

  • ROS 2 Foxy Fitzroy installed on Ubuntu Linux 20.04 or newer. I am using ROS 2 Galactic, which is the latest version of ROS 2 as of the date of this post.
    • If you are using another ROS 2 distribution, you will need to replace ‘galactic’ with the name of your distribution everywhere I mention ‘galactic’ in this tutorial. 
    • I highly recommend you get the newest version of ROS 2. If you are using a newer version of ROS 2, you can still follow all the steps in this tutorial. Everything will work just fine.
  • You have already created a ROS 2 workspace. The name of our workspace is “dev_ws”, which stands for “development workspace.” 
  • (Optional) You have a package named two_wheeled_robot inside your ~/dev_ws/src folder, which I set up in this post. If you have another package, that is fine.

Manually 

Quick Start

The easiest way to load a world is via the command line. 

Open a new terminal window.

Type the following command to open up a world named cafe.world. This file is one of the built-in worlds that comes with the Gazebo installation (I am using Gazebo 11).

gazebo worlds/cafe.world

You can see a list of all the built-in worlds in this GitHub repository.

The world files are located in your /usr/share/gazebo-11/worlds directory.

The models (i.e. models for the objects that are inside your world) are located inside this directory:

~/.gazebo/models

Where focalfossa is the name of your Linux environment.

When you want to close the world, go back to the terminal, and type:

CTRL + C

Your Own World

If you have your own world, you can follow the instructions on this post to test it in Gazebo.

Alternatively, you can launch Gazebo using the following command.

gazebo

Then go to the Insert tab, and start inserting items inside the empty world. 

2-click-insert-tab
3-insert-an-airplane

Once you’re done, you can save the world file by going to File ->Save World As.

Using a Launch File

Example – Cafe World

Let’s launch the cafe world we saw earlier using a ROS 2 launch file.

I want to copy the cafe.world file to the worlds folder of my ROS 2 package.

cd /usr/share/gazebo-11/worlds
cp cafe.world ~/dev_ws/src/two_wheeled_robot/worlds
3b-worlds-file-cafe

The syntax is:

cp <world file> <path to the worlds folder inside your ROS 2 package>

cd ~/dev_ws/src/two_wheeled_robot/worlds
gedit cafe.world

You will see the cafe.world file has various links to other models and mesh files in it. Let’s move those files over to our package so that everything is all inside our two_wheeled_robot package (or whatever ROS 2 package you’re using).

Start from the top of the cafe.world file.

The first model we need to move over is the ground_plane model.

cd ~/.gazebo/models
cp -r ground_plane ~/dev_ws/src/two_wheeled_robot/models

Now let’s copy over the other models.

cp -r cafe ~/dev_ws/src/two_wheeled_robot/models
cp -r cafe_table ~/dev_ws/src/two_wheeled_robot/models
4-models-files

Now let’s create a launch file.

colcon_cd two_wheeled_robot
cd launch
gedit load_world_into_gazebo.launch.py

Write this code inside the file.

# Author: Addison Sears-Collins
# Date: September 19, 2021
# Description: Load a world file into Gazebo.
# https://automaticaddison.com

import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.conditions import IfCondition, UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import Command, LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

def generate_launch_description():

  # Set the path to the Gazebo ROS package
  pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros')   
  
  # Set the path to this package.
  pkg_share = FindPackageShare(package='two_wheeled_robot').find('two_wheeled_robot')

  # Set the path to the world file
  world_file_name = 'cafe.world'
  world_path = os.path.join(pkg_share, 'worlds', world_file_name)
  
  # Set the path to the SDF model files.
  gazebo_models_path = os.path.join(pkg_share, 'models')
  os.environ["GAZEBO_MODEL_PATH"] = gazebo_models_path

  ########### YOU DO NOT NEED TO CHANGE ANYTHING BELOW THIS LINE ##############  
  # Launch configuration variables specific to simulation
  headless = LaunchConfiguration('headless')
  use_sim_time = LaunchConfiguration('use_sim_time')
  use_simulator = LaunchConfiguration('use_simulator')
  world = LaunchConfiguration('world')

  declare_simulator_cmd = DeclareLaunchArgument(
    name='headless',
    default_value='False',
    description='Whether to execute gzclient')
    
  declare_use_sim_time_cmd = DeclareLaunchArgument(
    name='use_sim_time',
    default_value='true',
    description='Use simulation (Gazebo) clock if true')

  declare_use_simulator_cmd = DeclareLaunchArgument(
    name='use_simulator',
    default_value='True',
    description='Whether to start the simulator')

  declare_world_cmd = DeclareLaunchArgument(
    name='world',
    default_value=world_path,
    description='Full path to the world model file to load')
   
  # Specify the actions
  
  # Start Gazebo server
  start_gazebo_server_cmd = IncludeLaunchDescription(
    PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
    condition=IfCondition(use_simulator),
    launch_arguments={'world': world}.items())

  # Start Gazebo client    
  start_gazebo_client_cmd = IncludeLaunchDescription(
    PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')),
    condition=IfCondition(PythonExpression([use_simulator, ' and not ', headless])))

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

  # Declare the launch options
  ld.add_action(declare_simulator_cmd)
  ld.add_action(declare_use_sim_time_cmd)
  ld.add_action(declare_use_simulator_cmd)
  ld.add_action(declare_world_cmd)

  # Add any actions
  ld.add_action(start_gazebo_server_cmd)
  ld.add_action(start_gazebo_client_cmd)

  return ld

Save the file, and close it.

Go to your root directory.

cd ~/dev_ws

Build the package.

colcon build

Open a new terminal window.

Run the launch file using the following command:

ros2 launch two_wheeled_robot load_world_into_gazebo.launch.py

Here is the output. You should see the actors walking around the cafe.

5-cafe-world

Summary

In summary, the procedure for creating a world entails the following steps:

  1. Create the .world file inside the worlds folder of your package.
  2. Add the SDF models to the models folder of your package.
  3. Edit the launch file.
  4. Build the package.
  5. Launch the world.