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

Installation

  1. Install gazebo and its ROS components with sudo apt install ros-jazzy-simulation
  2. Tutorials for Gazebo Harmonic (Harmonic is the version name)

Running

  1. Run gazebo with ros2 launch ros_gz_sim gz_sim.launch.py
    • This launchfile provides a method to pass options to gazebo by specifying gz_args:=<args to gazebo>
    • The gz command can also launch gazebo directly (this is the non-ros method of starting gazebo).
  2. ros_gz provides the primary method for interacting with Gazebo via ROS 2

Package Layout

  1. Typically, xacro files go under the urdf directory in the package
  2. SDF files for worlds go in a worlds/ directory and are installed to share/<pkg_name>/worlds
  3. SDF files for models go in a models/ directory and are installed to share/<pkg_name>/models
  4. The GZ_SIM_<SOMETHING>_PATH environment variables tells gazebo where to find SDF files and other resources

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

      prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share/<pkg_name>/models
      prepend-non-duplicate;GZ_SIM_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 the hook is installed properly, after source install/setup.bash, echo $GAZEBO_RESOURCE_PATH should contain the paths to the gazebo resources
  5. An example of this package layout can be found at https://github.com/m-elwin/me495_gazebo.
  6. In ROS 1, these paths were handled in the package.xml with special Gazebo tags. It seems like similar functionality is being introduced into ROS 2, though we are not currently adopting this practice: see Transitional Documentation for more information.

SDF Files

  • Gazebo uses SDF files to represent robots, worlds, and everything that appears in the simulation.
  • 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

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.
  • Additional sdf tags can be added to a URDF by using the <gazebo> tag, which provide additional flexibility when converting a URDF to an SDF

    <robot xmlns:xacro="http://www.ros.org/wiki/xacro>
    <gazebo>
    <!-- Resulting SDF file will have all the SDF tags here and will be associated with the full robot model at the top-level-->
    </gazebo>
    <gazebo reference="link_name">
    <!-- resulting SDF file will have these SDF tags under the link named "link_name" -->
    </gazebo>
    <gazebo reference="joint_name">
    <!-- resulting SDF file will have these SDF tags under the joint named "joint_name" -->
    </gazebo>
    </robot>
    
  • A typical project structure is for a robot to provide:
    1. A robot.urdf.xacro file that contains robot definition without any gazebo tags.
    2. A robot.gazebo.xacro file that includes only the tags necessary for gazebo
    3. robot.urdf.xacro takes an argument (e.g., gazebo that conditionally includes robot.gazebo.xacro.
      • If the argument is true, the robot.gazebo.xacro file is included
      • If the argument is false, the robot.gazebo.xacro file is NOT included, and the resulting URDF file is free of any gazebo dependencies
  • For a URDF model to be loaded in gazebo successfully, it is required that all links have visual, collision and inertia specified.
  • 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

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 gz 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 gz::sim::systems::DiffDrive plugin:
        • Set name to gz::sim::systems::DiffDrive
        • set filename to libgz-sim-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 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 second @ in 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)
        • Replacing the second @ with a [ creates a bridge from Gazebo to ROS and using a ] creates a bridge from ROS to Gazebo
      • Sometimes uni-directional bridges are necessary. 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
  4. The Gazebo ROS 2 Bridge Documentation provides more information.

Software in Transition

As of 10/2024: There are three simultaneous transitions happening that have resulted in rapid churn in how ROS 2 and Gazebo works, which can make navigating online sources difficult:

  1. Transition from ROS to ROS 2
    • Although the transition is mostly complete there are still many references to "using Gazebo" which refer to ROS 1 and Gazebo Classic.
  2. Transition from Gazebo Classic (i.e., the original Gazebo Simulator ) to Gazebo (e.g., the new Gazebo Simulator)
    • This transition also seems to be mostly complete: to make sure you are reading information on Gazebo (and not Gazebo Classic), ensure that the url does not contain classic.gazebosim.org
  3. The renaming of Ignition Gazebo to Gazebo and the renaming of Gazebo to Gazebo Classic
  4. ROS 2 now distributes it's own "vendored" version of Gazebo with each ROS 2 release (before this was separate)
    • These packages appear to be installed under /opt/ros/jazzy/opt which is strange, maybe it's to avoid name conflicts but it ends up polluting the path quite a bit.
  5. A new method of Gazebo ROS 2 Integration, which looks promising but does not seem to be fully implemented or feature complete.
    • It allows starting the gazebo_server using a <gz_server> tag in a Launchfile (excellent!)
    • The server can run in a container as a composable node (great!)
    • The ROS 2 Gazebo Bridge can also run in the composable Node and has it's own xml launchfile tag (wonderful!)
    • The create_own_container attribute does not seem to be implemented in the currently released Jazzy version of ros_gz_sim package (though it is in the code…??)
    • There does not seem to be a straightforward way (or at least I have not found one) to start the Gazebo Gui client for use with the <gz_server>
      • gz sim -g sometimes connects to the server and sometimes does not: simply starting and restarting it a few times seems to work but it is unreliable on my system (might need to just do a bit more debugging here).
        • It would be, in my opinion, a useful contribution to add the capability to run the Gazebo Gui as a component node and launch it with a <gz_client> tag from a launchfile.
    • The migration to the ROS 1 way of handling Gazebo Paths (custom tags in package.xml) versus the ROS 2 way (using colcon env-hooks) may be better long-term, but it's implementation relies on using certain launchfiles which we cannot fully use currently.
    • The demonstrations for ros_gz_sim do not seem updated for the new method.
    • Overall, I would like to adopt the new methods, but their still seems to be a mix of documentation promoting the new methods, examples with the old methods. Hopefully by next year this will be a bit more mature.
  6. There is also talk of maintaining robots as SDF files rather than URDF files. I have not yet seen this in practice, and am hesitant to adopt this practice given that SDF files are more general than URDF files (so URDF can always be converted to SDF but not vice-versa).

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)

Open Source Simulators

Current Simulators

  • MuJoCo - A dynamics simulator specifically built for robotics tasks. This is likely one of the more state-of-the-art simulators.
    • Purchased by DeepMind, which has made it open-source (formerly was very expensive and proprietary).
  • Drake C++ Simulation tools for dynamic robots, using optimization techniques.
    • Started at MIT, now backed by Toyota Research.
    • High-fidelity simulation (particularly for contacts), at the expense of simulation speed.
    • User has visibility into all algorithms and principles used in computation of the simulation
  • Project Chrono - A multi-physics simulation.
    • Does finite elements, granular material, real physics that takes a long time to compute.
    • Only recommended if you have a specific need for high-fidelity physics
  • Webbots - Robot simulator with a long history. Just released a new version in 2023

Less Maintained

  • pybullet - A pythons simulator based on Bullet.
    • Formerly popular in the reinforcement-learning community, still some residual use.
    • Ever since MuJoCo became open-source, it's popularity has waned.
  • trep - Developed in Todd Murphey's lab. Good numerical algorithms and transparency in how the dynamics are actually solved. Does not support contact/friction.

Closed Source Simulators

  • CoppeliaSim (formerly V-Rep)
    • Free for educational use, but not open source.
  • Isaac Sim
    • Popular due to its speed (for RL training) and good rendering (can learn from objects rendered in simulation and transfer to real world).
    • Ubuntu 24.04 and ROS 2 Jazzy are not yet supported (as of 10/2024).

Author: Matthew Elwin.