UP | HOME

Simulation

Overview

Computer simulations represent the physical world as a set of state variables and perform computations to advance this state forward (or backward) in time.

In robotics, simulation is used to perform robotic experiments without requiring robotic hardware. Instead, a mathematical model of the robot and its environment is used to approximate the behavior of a real robot.

Advantages of Simulation

  • You control all variables and can replay identical scenarios
  • You can inspect and set the full state of the system accurately
  • You can easily change properties of the robot, sensors, and the environment
  • The robot does not break or run out of battery power

Disadvantages of Simulation

  • Behavior differs from the real world
  • Only effects that are already modeled and known can be examined
  • Even if an effect is modeled, numerical error can become an issue
  • Simulated robots can't vacuum your floor

Choosing a simulator

Identifying What Must Be Modeled

The needs of your robotic application dictate the complexity of your model and the requirements for your simulation engine. Choosing the correct level of simulated detail is an important design choice: the more detail, the more accuracy, but also the more computation time and complexity.

Here are some types of simulations used in robotics:

  • Discrete Position
    • Robots are agents that can move from grid-space to grid-space
    • The mechanics of the movement are ignored
  • Kinematic
    • Control positions and velocities of the joints
  • Dynamic
    • Robots and objects have inertia and you control forces and torques
    • Newton's Laws or Euler Lagrange can be used
    • Complexity of the dynamic effects modeled can vary widely
  • Finite Element
    • Parts of the robot can deform according to stress-strain relations
  • Fluid Dynamics
    • For underwater or aerial robots

Differences Between Simulation Engines

  1. What integration scheme do they use?
    • Most simulations ultimately hinge on integrating differential equations
    • Many simulators provide a choice or parameters that can be tuned
    • Accuracy vs speed trade-offs
    • Specific types of differential equations may be better suited to different integration schemes
  2. What phenomenon can be modeled?
    • Collisions?
    • Friction?
    • Lighting conditions?
    • Aerodynamics?
  3. Visualization tools?
    • Can you view the simulated objects?
    • Can you generate plots based on the simulation?
    • How do you provide input?
    • How do you read the output?
  4. What robots are supported?
    • Specific to certain types of robots?
    • General purpose, can make nearly anything?
    • Are their pre-built models available?

Custom Simulators

  • Sometimes, you have a simple model for your robot
  • Using a simple model, you can usually write your own simulator
  • In some cases, writing your own can be simpler than invoking a complicated general purpose simulator like gazebo.
  • Writing a simulation for a robot is a good way to verify you understand the system

Gazebo

  • The Gazebo simulator is the main simulator for ROS
  • Like ROS, it is maintained by the Open Source Robotics Foundation, but it is a standalone program
  • Many concepts in Gazebo are similar to ROS but slightly different
  • We will focus on how to use Gazebo from ROS
  • Carefully designed ROS programs can seamlessly switch between controlling a Gazebo simulation and a real robot.
  • We use Gazebo 11, the latest version of Gazebo and the one that is most easily paired with ROS noetic

Ignition Gazebo

  • Ignition Gazebo is a rewrite of Gazebo, an attempt to make it more modular and easier to access various physics engines and robotics math
  • Ignition Gazebo and Gazebo are two different systems made by the same people (like the relationship between ROS and ROS 2)
  • We are using Gazebo, not ignition gazebo because ignition gazebo is still in development and is not feature complete.

Gazebo Features

  • Choice of physics engines:
  • Graphics: Gazebo provides a graphical interface for viewing and creating simulated worlds. It is like a cross between RViz and a mini CAD program.
    • The appearance of objects in Gazebo is how they appear in simulated camera sensors
    • Think of the Gazebo display as being a stand-in for the real world and the RViz display is a visualization based off of what the robot senses.
  • Plugin Architecture: Everything in Gazebo is written as a C++ plugin.
    • This makes Gazebo extendable, and provides you with the ability to not only add new objects in Gazebo but also new physical phenomena
    • Gazebo comes with many plugins, representing, for example, different types of sensors
    • ROS support for Gazebo is provided by a plugin
  • Network: Like ROS, gazebo consists of multiple processes that communicate with each other using network protocols (different from those in ROS). However, Gazebo can be, for example, run on another remote server.

Gazebo and ROS

  • ROS uses URDF files to represent robots
  • Gazebo uses SDF files to represent robots and other objects
  • Gazebo provides extensions to URDF files that enable it to convert URDF to SDF automatically

How to Learn Gazebo

Gazebo has many excellent tutorials. It also has its own question/answer website. I've created a guide below focusing on how to integrate Gazebo into what you already know about ROS. The more tutorials you go through the better, but you should at least go through the ones listed below.

  1. Basic Guide
  2. Connect to ROS Tutorials
    • ROS Overview
    • Using roslaunch
      • This tutorial also explains how to export your gazebo models form your ros package
    • URDF in Gazebo
    • Gazebo Plugins in ROS
      • Essentially, plugins are how you add sensors to your URDF for use in Gazebo
      • Sensor plugins will publish sensor messages to ROS. They correspond to actual sensors and tend to publish the same messages as their physical counterparts
    • Ros Control
      • The ROS Control package lets you control a simulated and real robot using the same code
      • <transmission> tags in the urdf are required to make this work
      • See also ros_control
    • ROS communication
      • Gazebo provides a ROS api for controlling it and getting information from it

Some Other Simulators (for reference, we will not use these)

  • pybullet - A pythons simulator based on Bullet. Very popular in the reinforcement-learning community
    • I often recommend this simulator because it is more lightweight than Gazebo and can easily be integrated with ROS
  • MuJoCo - A dynamics simulator specifically built for robotics tasks. This is likely one of the more state-of-the-art simulators.
    • Now owned by DeepMind, which is making it free
  • Drake C++ Simulation tools for dynamic robots, using optimization techniques. Started at MIT, now backed by Toyota Research.
  • Project Chrono - A multi-physics simulation. Does finite elements, granular material, real physics that takes a long time to compute
  • CoppeliaSim (formerly V-Rep) Free for educational use, but not 100% open source. Has some ROS integration, scripted in Lua.
  • trep - Developed in Todd Murphey's lab. Good numerical algorithms and transparency in how the dynamics are actually solved. Does not support contact/friction.
  • Webbots - Robot simulator with a long history. Just released a new version in 2020

Author: Matthew Elwin