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 Classic

  • The Gazebo Classic (or the simulator formerly known as Gazebo) is the main simulator for ROS 1
  • 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.

Gazebo

  • Gazebo (Formerly called Ignition Gazebo) is the latest simulator developed by Open Robotics

Gazebo Features

  • Choice of physics engines:
    • By default it uses the Dart physics engine
  • Graphics: Gazebo provides a graphical interface for viewing and creating simulated worlds.
    • 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.
    • Gazebo has powerful rendering features that are aimed at creating photo-realistic models so that computer vision in the simulator can be useful
  • 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. There are counterparts to ROS mesages and services,but these are entirely different systems

Gazebo and ROS

  1. Install gazebo and its ROS components with sudo apt install ros-iron-simulation
  2. Tutorials for Gazebo Fortress (fortress is the version name)
  3. Run gazebo with ros2 launch ros_gz_sim gz_sim.launch.py
    • This launchfile provides a method to pass options to gazebo
    • The ign command can also launch gazebo directly (this is the non-ros method of starting gazebo).
  4. ros_gz provides the primary method for interacting with Gazebo via ROS 2

SDF Files

  • 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
  • SDF Tutorials provides help with writing SDF files, including building worlds
  • Fuel is a library where people share SDF models and worlds. The website contains functionality to preview, download, and link-to assets for simulation
  • Typically, the Gazebo-specific parts of the URDF are kept in a separate file called <robotname>.gazebo.xacro
  • Using the xacro:include tag (and with the $(find package) substitution), the main URDF file loads the gazebo file

Loading URDF/SDF files

  • ROS can be used to load both URDF and SDF models into the simulator
  • URDF files are automatically converted to SDF prior to being loaded
  • ros2 run ros_gz_sim create is a ROS node that can load urdf/sdf data into gazebo
    • The data can come from a file, a parameter, a topic, or a string
    • Typically, you will load the data from the /robot_description topic
    • ros2 run ros_gz_sim create --help for all the options
  • Additional sdf tags can be added to a URDF by using the <gazebo> tag
    • <gazebo>sdftags go here</gazebo> associates the SDF tags with the full model
      • Useful for adding model-wide plugins like the diff-drive robot
    • <gazebo reference="">sdftags go here</gazebo> associates the SDF tag with the specified link or joint
  • For a URDF model to be loaded in gazebo successfully, it requires, at a minimum:
    • All links must have visual, collision, and inertia

Debugging

It can be helpful to inspect urdf files at different stages of conversion, especially if there are errors when trying to load your model.

  1. Make sure the files are installed via setup.py
  2. Source the workspace
  3. Run xacro ./install/path_to_xacro_file > robot.urdf to produce the URDF file
  4. Run ign sdf -p robot.urdf > robot.sdf to produce the SDF file

Plugins

  1. Gazebo uses plugins to enhance/modify functionality
  2. Some plugins can be associated with specific models and used to control them
  3. Useful Plugins can be found in the API documentation, especially the Systems.
    • The documentation includes what tags can be used in the SDF to include the plugin
    • Use <plugin name="<C++ Namespace Path of the plugin>" filename="lib_object_with_the_code">
      • For example, to use the ignition::gazebo::systems::DiffDrive plugin:
        • Set name to ignition::gazebo::systems::DiffDrive
        • set filename to libignition-gazebo-diff-drive-system.so
        • Options for this plugin go inside the <plugin></plugin> tag (see API Documentation)
  4. The JointStatePublisher plugin publishes joint states

Bridging

  1. The ROS GZ Bridge is used to connect ROS topics and services to Gazebo topics and services
    • ros2 run ros2 run ros_gz_bridge parameter_bridge topic@ros_type@gz_type
      • Provide the topic name, the ROS type, and the corresponding gazebo type
      • Use --help for options/syntax
      • The above syntax starts a bi-directional bridge (e.g. topics from gazebo are published to ros and topics from ros are published to gazebo)
      • Sometimes uni-directional bridges are desired. For example, we may want to receive tf frames from Gazebo without having all of ROS's Tf frames existing in the simulator.
      • Be careful about topic types: for example the ROS type of the /tf topic is TFMessage not TransformStamped
  2. You should generally run one ros_gz_bridge and specify all topics/services that must be bridged
  3. Once the bridge is running you can publish/subscribe to the topics like any other ROS topic

Bridge Directions

Package Layout

  1. Typically, xacro files go under the urdf directory in the package
  2. SDF files for worlds go in a worlds/ directory
  3. SDF files for models go in a models/ directory
  4. The IGN_GAZEBO_RESOURCE_PATH environment variable tells gazebo where to find SDF files

    • A ROS package that provides gazebo resources needs to set this variable appropriately.
    • Create a .dsv file in the env-hooks directory with the following content (be sure to update the <pkg_name> to be the name of the package):

      prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share/<pkg_name>/models
      prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share/<pkg_name>/worlds
      
    • Follow the colcon.pkg instructions to install the hook and have it update the environment whenever you source install/setup.bash
      • When this is done properly, after source install/setup.bash, echo $IGN_GAZEBO_RESOURCE_PATH should contain the paths to the gazebo resources

Documentation

  1. Gazebo Tutorials
  2. SDF Format
  3. ROS 2 Gazebo Interface (See the README.md files in each package in the repository
  4. Fuel Model Library

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