Differential Drive Robot Teleop - dhanushshettigar/Getting-Started-With-ROS2 GitHub Wiki

Launching a Differential Drive Robot in a Custom Gazebo World with ROS 2

Table of Contents:

  1. Package Overview
  2. Package Creation
  3. Vehicle Model Creation
  4. World SDF File Configuration
  5. Launch File Creation
  6. Modifying the Setup File
  7. Modifying the Package File
  8. Package Dependencies and Installation
  9. Building and Sourcing the Package
  10. Launching the Package
  11. Teleoperate the Robot

1. Package Overview

This guide explains the process of creating a custom ROS 2 package for a differential drive robot. It covers the steps required to configure the vehicle model, define the simulation world in Gazebo, and integrate the necessary launch files to launch the simulation.


2. Package Creation

1. Create the ROS 2 Package:

To begin, create a new ROS 2 package in ros2 worskpase using the following command:

ros2 pkg create diff_robot_custom_world --build-type ament_python

2. Navigate to the Package Directory:

After creating the package, navigate to the package directory:

cd diff_robot_custom_world && code .

3. Create Directories for Models and Worlds:

In the VS Code editor, create two new directories under the package: models and worlds.

3. Vehicle Model Creation

1. Create Vehicle Model Directory:

Inside the models directory, create a folder named vehicle and a file named model.sdf.

2. File Structure:

The directory structure should look like this:

Models
  └── vehicle
      ├── model.sdf
      └── model.config

3. Define the Model in SDF:

Add the following SDF (Simulation Description Format) content to model.sdf to describe the vehicle and its components.

<?xml version="1.0" ?>
<sdf version="1.8">
    <model name='vehicle'>
        <link name='chassis'>
            <pose>-0.075714 0 0.147181 0 0 0</pose>
            <inertial>
                <mass>0.571975</mass>
                <inertia>
                    <ixx>0.063082</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>0.2082595</iyy>
                    <iyz>0</iyz>
                    <izz>0.240507</izz>
                </inertia>
            </inertial>
            <visual name='visual_chassis'>
                <geometry>
                    <box>
                        <size>1.00571 0.5 0.284363</size>
                    </box>
                </geometry>
                <material>
                    <ambient>0.5 0.5 1.0 1</ambient>
                    <diffuse>0.5 0.5 1.0 1</diffuse>
                    <specular>0.0 0.0 1.0 1</specular>
                </material>
            </visual>
            <collision name='collision_chassis'>
                <geometry>
                    <box>
                        <size>1.00571 0.5 0.284363</size>
                    </box>
                </geometry>
            </collision>
        </link>

        <link name='left_wheel'>
            <pose>0.277142 0.3125145 -0.0125 -1.5707 0 0</pose>
            <inertial>
                <mass>1</mass>
                <inertia>
                    <ixx>0.0729165</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>0.0729165</iyy>
                    <iyz>0</iyz>
                    <izz>0.0625</izz>
                </inertia>
            </inertial>
            <visual name='visual_left_wheel'>
                <geometry>
                    <sphere>
                        <radius>0.15</radius>
                    </sphere>
                </geometry>
                <material>
                    <ambient>0.2 0.2 0.2 1</ambient>
                    <diffuse>0.2 0.2 0.2 1</diffuse>
                    <specular>0.2 0.2 0.2 1</specular>
                </material>
            </visual>
            <collision name='collision_left_wheel'>
                <geometry>
                    <sphere>
                        <radius>0.15</radius>
                    </sphere>
                </geometry>
            </collision>
        </link>

        <link name='right_wheel'>
            <pose>0.277141 -0.3125145 -0.0125 -1.5707 0 0</pose>
            <inertial>
                <mass>1</mass>
                <inertia>
                    <ixx>0.0729165</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>0.0729165</iyy>
                    <iyz>0</iyz>
                    <izz>0.0625</izz>
                </inertia>
            </inertial>
            <visual name='visual_right_wheel'>
                <geometry>
                    <sphere>
                        <radius>0.15</radius>
                    </sphere>
                </geometry>
                <material>
                    <ambient>0.2 0.2 0.2 1</ambient>
                    <diffuse>0.2 0.2 0.2 1</diffuse>
                    <specular>0.2 0.2 0.2 1</specular>
                </material>
            </visual>
            <collision name='collision_right_wheel'>
                <geometry>
                    <sphere>
                        <radius>0.15</radius>
                    </sphere>
                </geometry>
            </collision>
        </link>

        <link name='caster'>
            <pose>-0.478569 0 -0.0625 0 -0 0</pose>
            <inertial>
                <mass>0.5</mass>
                <inertia>
                    <ixx>0.05</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>0.05</iyy>
                    <iyz>0</iyz>
                    <izz>0.05</izz>
                </inertia>
            </inertial>
            <visual name='visual_caster'>
                <geometry>
                    <sphere>
                        <radius>0.1</radius>
                    </sphere>
                </geometry>
                <material>
                    <ambient>0.2 0.2 0.2 1</ambient>
                    <diffuse>0.2 0.2 0.2 1</diffuse>
                    <specular>0.2 0.2 0.2 1</specular>
                </material>
            </visual>
            <collision name='collision_caster'>
                <geometry>
                    <sphere>
                        <radius>0.1</radius>
                    </sphere>
                </geometry>
            </collision>
        </link>

        <joint name='left_wheel_joint' type='revolute'>
            <parent>chassis</parent>
            <child>left_wheel</child>
            <axis>
                <xyz>0 0 1</xyz>
                <limit>
                    <lower>-1.79769e+308</lower>
                    <upper>1.79769e+308</upper>
                </limit>
            </axis>
        </joint>

        <joint name='right_wheel_joint' type='revolute'>
            <parent>chassis</parent>
            <child>right_wheel</child>
            <axis>
                <xyz>0 0 1</xyz>
                <limit>
                    <lower>-1.79769e+308</lower>
                    <upper>1.79769e+308</upper>
                </limit>
            </axis>
        </joint>

        <joint name='caster_wheel' type='ball'>
            <parent>chassis</parent>
            <child>caster</child>
        </joint>

        <plugin
            filename="ignition-gazebo-diff-drive-system"
            name="ignition::gazebo::systems::DiffDrive">
            <left_joint>left_wheel_joint</left_joint>
            <right_joint>right_wheel_joint</right_joint>
            <wheel_separation>0.625</wheel_separation>
            <wheel_radius>0.15</wheel_radius>
            <odom_publish_frequency>1</odom_publish_frequency>
            <max_linear_acceleration>1</max_linear_acceleration>
            <min_linear_acceleration>-1</min_linear_acceleration>
            <max_angular_acceleration>2</max_angular_acceleration>
            <min_angular_acceleration>-2</min_angular_acceleration>
            <max_linear_velocity>0.5</max_linear_velocity>
            <min_linear_velocity>-0.5</min_linear_velocity>
            <max_angular_velocity>1</max_angular_velocity>
            <min_angular_velocity>-1</min_angular_velocity>
        </plugin>

    </model>
</sdf>

Explanation of the DiffDrive Plugin Configuration in SDF

The <plugin> element defines the behavior of the differential drive system for the robot. This plugin is part of the Ignition Gazebo system and manages the control and movement of the robot based on the wheel velocities. Below is a breakdown of the parameters:


Plugin Attributes

  • filename="ignition-gazebo-diff-drive-system": Specifies the library file for the differential drive system plugin.
  • name="ignition::gazebo::systems::DiffDrive": Identifies the plugin's class or system to be used.

Key Parameters

Parameter Value Description
<left_joint> left_wheel_joint Specifies the name of the joint for the left wheel.
<right_joint> right_wheel_joint Specifies the name of the joint for the right wheel.
<wheel_separation> 0.625 Distance between the centers of the left and right wheels.
<wheel_radius> 0.15 Radius of the wheels. Determines how wheel rotations translate to movement.
<odom_publish_frequency> 1 Frequency (in Hz) at which odometry data is published.
<max_linear_acceleration> 1 Maximum allowable forward acceleration for the robot.
<min_linear_acceleration> -1 Minimum allowable (backward) acceleration for the robot.
<max_angular_acceleration> 2 Maximum allowable angular (rotational) acceleration.
<min_angular_acceleration> -2 Minimum allowable angular (rotational) deceleration.
<max_linear_velocity> 0.5 Maximum forward velocity of the robot (m/s).
<min_linear_velocity> -0.5 Maximum backward velocity of the robot (m/s).
<max_angular_velocity> 1 Maximum angular velocity (rad/s), controlling how fast the robot can rotate.
<min_angular_velocity> -1 Minimum angular velocity (rad/s), controlling the reverse rotation speed.

Behavior

This configuration:

  • Links the robot's movement to the left and right wheel joints.
  • Allows the robot to move forward, backward, or rotate in place.
  • Sets limits on how fast and how much the robot can accelerate or turn, ensuring smooth and controlled motion.
  • The odometry data is published at a frequency of 1 Hz, providing position and orientation feedback for navigation systems.

This plugin enables precise control of the robot's movements within a simulated environment, adhering to the physical constraints defined in the parameters.

4. Create model.config File:

Define the model configuration in model.config:

<?xml version="1.0"?>
<model>
    <name>vehicle</name>
    <version>1.0</version>
    <sdf version="1.6">model.sdf</sdf>
    <author>
        <name>Your Name</name>
        <email>[email protected]</email>
    </author>
    <description>A simple vehicle model for use in custom Gazebo worlds.</description>
</model>

4. World SDF File Configuration

1. Create World File:

Inside the worlds directory, create a file named my_world.sdf and add your world configuration.

<?xml version="1.0" ?>
<sdf version='1.8'>
  <world name="my_world">
    <physics name='1ms' type='ignored'>
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1</real_time_factor>
      <real_time_update_rate>1000</real_time_update_rate>
    </physics>
    <plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
    <plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
    <plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
    <plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
    <plugin filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors">
       <render_engine>ogre2</render_engine>
    </plugin>
    <gravity>0 0 -9.8</gravity>
    <magnetic_field>5.5645e-06 2.28758e-05 -4.23884e-05</magnetic_field>
    <atmosphere type='adiabatic'/>
    <scene>
      <ambient>0.4 0.4 0.4 1</ambient>
      <background>0.7 0.7 0.7 1</background>
      <shadows>true</shadows>
    </scene>

    <model name='ground_plane'>
      <static>true</static>
      <link name='link'>
        <collision name='collision'>
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <bounce/>
            <contact/>
          </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>
        <pose>0 0 0.001 0 0 0</pose>
      </link>
    </model>

    <include>
      <uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/Reflective table</uri>
      <name>Reflective table</name>
      <pose>2.122251033782959 0 -4.6018890569922924e-19 0 2.1684043449710089e-19 0</pose>
    </include>
    <include>
      <uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/OfficeChairGrey</uri>
      <name>OfficeChairGrey</name>
      <pose>1.9308624267578125 0.63945025205612183 0 0 0 1.5665299667756876</pose>
    </include>
    <include>
      <uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/OfficeChairGrey</uri>
      <name>OfficeChairGrey_1</name>
      <pose>1.9722961266891872 -0.45148325981242099 0 0 0 1.5665299667756876</pose>
    </include>

    <light name='sun' type='directional'>
      <pose>0 0 10 0 0 0</pose>
      <cast_shadows>true</cast_shadows>
      <intensity>1</intensity>
      <direction>-0.5 0.1 -0.9</direction>
      <diffuse>0.8 0.8 0.8 1</diffuse>
      <specular>0.2 0.2 0.2 1</specular>
      <attenuation>
        <range>1000</range>
        <linear>0.01</linear>
        <constant>0.9</constant>
        <quadratic>0.001</quadratic>
      </attenuation>
      <spot>
        <inner_angle>0</inner_angle>
        <outer_angle>0</outer_angle>
        <falloff>0</falloff>
      </spot>
    </light>
  </world>
</sdf>

Explanation of the Plugin Configuration in SDF

The following plugins are used to enhance the functionality of the simulation in Gazebo (Ignition). Each plugin serves a specific purpose related to the simulation of physics, user commands, scene broadcasting, contact handling, and sensors.


Plugins and Their Functions

Plugin Name Filename Description
gz::sim::systems::Physics gz-sim-physics-system This plugin handles the physics simulation system, responsible for calculating forces, accelerations, and interactions in the simulation environment.
gz::sim::systems::UserCommands gz-sim-user-commands-system Handles user input commands, allowing interaction with the simulation through custom or predefined commands.
gz::sim::systems::SceneBroadcaster gz-sim-scene-broadcaster-system Responsible for broadcasting the simulation scene to external systems, enabling visualization or monitoring of the simulation.
gz::sim::systems::Contact gz-sim-contact-system This plugin manages the contact forces and interactions between objects in the simulation, essential for collision detection and response.
gz::sim::systems::Sensors gz-sim-sensors-system Manages the sensors in the simulation, such as cameras, lidars, and other sensing devices. The <render_engine> tag specifies that the rendering engine to be used for sensors is OGRE2.

Special Configuration for Sensors Plugin

  • <render_engine>ogre2</render_engine>: Specifies that the rendering engine used for visualizing sensor data in the simulation will be OGRE2 (Object-Oriented Graphics Rendering Engine). OGRE2 is used for high-performance, visually accurate rendering in 3D environments.

2. Include the Vehicle Model in the World File:

Modify the world file to include the vehicle model:

    <model name="vehicle">
      <self_collide>true</self_collide>
      <pose>0 0 0.294363 0 0 0</pose>
      <include merge="true">
        <uri>file:///<ROS2 Workspace Location>/install/diff_robot_custom_world/share/diff_robot_custom_world/models/vehicle</uri>
      </include>      

      <plugin
        filename="gz-sim-joint-state-publisher-system"
        name="gz::sim::systems::JointStatePublisher">
      </plugin>

      <plugin
        filename="gz-sim-pose-publisher-system"
        name="gz::sim::systems::PosePublisher">
        <publish_link_pose>true</publish_link_pose>
        <use_pose_vector_msg>true</use_pose_vector_msg>
        <static_publisher>true</static_publisher>
        <static_update_frequency>1</static_update_frequency>
      </plugin>

      <plugin
        filename="gz-sim-odometry-publisher-system"
        name="gz::sim::systems::OdometryPublisher">
        <odom_frame>vehicle/odom</odom_frame>
        <robot_base_frame>vehicle</robot_base_frame>
      </plugin>
    </model>

Explanation of the Model Configuration in SDF

This SDF (Simulation Description Format) configuration defines a vehicle model with several plugins to handle joint states, pose publishing, and odometry in the simulation.


Model Details

  • <model name="vehicle">: The model is named "vehicle", representing the robot or vehicle in the simulation.
  • <self_collide>true</self_collide>: This enables self-collision detection for the vehicle model, meaning the vehicle can collide with itself (useful for checking if parts of the vehicle interact or overlap during simulation).
  • <pose>0 0 0.294363 0 0 0</pose>: Sets the position and orientation of the vehicle model in the world. It is placed at coordinates (0, 0, 0.294363) with no rotation (0, 0, 0).
  • <include merge="true">: Includes another model or set of files into this vehicle model.
    • <uri>file:///<Your Workspace Location>/install/diff_robot_custom_world/share/diff_robot_custom_world/models/vehicle</uri>: Specifies the location of the model to include, pointing to a file directory where the vehicle's model files are located.

Plugins and Their Functions

  1. gz::sim::systems::JointStatePublisher

    • filename="gz-sim-joint-state-publisher-system": This plugin is used to publish the joint states of the robot. It ensures that the joint positions, velocities, and efforts are communicated in the simulation.
    • name="gz::sim::systems::JointStatePublisher": Specifies the system responsible for publishing the joint states.
  2. gz::sim::systems::PosePublisher

    • filename="gz-sim-pose-publisher-system": This plugin publishes the pose (position and orientation) of the robot model in the simulation.
    • <publish_link_pose>true</publish_link_pose>: This enables the publishing of the pose for each link of the robot.
    • <use_pose_vector_msg>true</use_pose_vector_msg>: The pose is published as a vector message, suitable for use with ROS or other systems that use vector-based pose representations.
    • <static_publisher>true</static_publisher>: The pose will be published at a constant rate, even if the model is not moving.
    • <static_update_frequency>1</static_update_frequency>: The pose will be updated and published once per second.
  3. gz::sim::systems::OdometryPublisher

    • filename="gz-sim-odometry-publisher-system": This plugin is responsible for publishing odometry information, which includes the position and velocity of the robot.
    • <odom_frame>vehicle/odom</odom_frame>: Defines the frame in which the odometry data will be expressed. In this case, it's the vehicle/odom frame.
    • <robot_base_frame>vehicle</robot_base_frame>: Specifies the base frame of the robot, which is vehicle in this configuration.

These plugins help with robot control, tracking, and state publishing, which are essential for interaction with ROS and other simulation systems.

5. Launch File Creation

Inside the launch directory, create a Python launch file diff_drive.launch.py to start the simulation.

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import IncludeLaunchDescription
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration

from launch_ros.actions import Node


def generate_launch_description():

    pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim')
    pkg_diff_robot_custom_world = get_package_share_directory('diff_robot_custom_world')

    world_file = os.path.join(pkg_diff_robot_custom_world, 'worlds', 'my_world.sdf')

    gz_sim = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')),
        launch_arguments={
            'gz_args': '-r ' + world_file
        }.items(),
    )

    rviz_node = Node(
        package='rviz2',
        executable='rviz2',
        output='screen',
    )

    bridge = Node(
        package='ros_gz_bridge',
        executable='parameter_bridge',
        arguments=[
            '/model/vehicle/cmd_vel@geometry_msgs/msg/[email protected]',
            '/model/vehicle/odometry@nav_msgs/msg/[email protected]',
        ],
        parameters=[{
            'qos_overrides./model/vehicle.subscriber.reliability': 'reliable',
        }],
        output='screen'
    )

    return LaunchDescription([
        gz_sim,
        DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'),
        bridge, 
        rviz_node
    ])

ROS 2-Gazebo Bridge

The bridge node establishes communication between ROS 2 and Gazebo by mapping topics between the two systems. Here's the detailed breakdown:

bridge = Node(
    package='ros_gz_bridge',
    executable='parameter_bridge',
    arguments=[
        '/model/vehicle/cmd_vel@geometry_msgs/msg/[email protected]',
        '/model/vehicle/odometry@nav_msgs/msg/[email protected]',
    ],
    parameters=[{
        'qos_overrides./model/vehicle.subscriber.reliability': 'reliable',
    }],
    output='screen'
)

Explanation

1.Package: ros_gz_bridge provides the capability to map and translate messages between ROS 2 and Gazebo. 2.Executable: parameter_bridge handles the topic translation.

Arguments

1./model/vehicle/cmd_vel:

  • Translates ROS 2 topic /model/vehicle/cmd_vel of type geometry_msgs/msg/Twist to the Gazebo topic gz.msgs.Twist.
  • This allows sending velocity commands from ROS 2 to a Gazebo model. 2./model/vehicle/odometry:
  • Translates the Gazebo topic gz.msgs.Odometry to the ROS 2 topic /model/vehicle/odometry of type nav_msgs/msg/Odometry.
  • This enables receiving odometry data from Gazebo in ROS 2.

Parameters

  • qos_overrides./model/vehicle.subscriber.reliability: reliable:
    • Overrides the Quality of Service (QoS) settings for the topic /model/vehicle to ensure reliable delivery of messages.

Output

  • output='screen': Logs messages and errors from the bridge node to the console for debugging.

This bridge is essential for seamless communication between the simulation environment (Gazebo) and ROS 2, enabling the use of ROS 2 tools and nodes with a Gazebo simulation.

6. Modifying the Setup File

Modify your setup.py to include the model and world files:

data_files=[
    ('share/ament_index/resource_index/packages', ['resource/' + package_name]),
    ('share/' + package_name, ['package.xml']),
    ('share/' + package_name + '/models/vehicle', [
        'models/vehicle/model.sdf',
        'models/vehicle/model.config'
    ]),
    ('share/' + package_name + '/worlds', ['worlds/my_world.sdf']),
    ('share/' + package_name + '/launch', ['launch/diff_drive.launch.py']),
],

7. Modifying the Package File

Modify your package.xml to include the dependencies

<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>ros_gz_bridge</exec_depend>
<exec_depend>ros_gz_sim</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_depend>

8. Package Dependencies and Installation

Ensure that you install the necessary dependencies before building the package:

sudo apt update
sudo apt install ros-jazzy-ros-gz-sim
sudo apt install ros-jazzy-ros-gz-bridge

9. Building and Sourcing the Package

1. Build the Package:

Build the ROS 2 package with the following command:

cd ../.. && colcon build --packages-select diff_robot_custom_world

2. Source the Package:

Source the package to make it available for use:

source install/setup.bash

10. Launching the Package

To launch the custom world with your differential drive robot, use:

export QT_QPA_PLATFORM=xcb && ros2 launch diff_robot_custom_world diff_drive.launch.py

11. Teleoperate the Robot

To teleoperate your robot using a UI (User Interface) in Gazebo, you can use various tools such as Ignition's built-in Teleoperation GUI, or you can implement a custom user interface using ROS 2 and the Ignition GUI plugin.

ROS2 Gazebo Teleop ROS2 Gazebo Teleop Video

⚠️ **GitHub.com Fallback** ⚠️