The simulation team at Open Robotics is happy to announce the release of Ignition integrations for ROS Noetic and Foxy! ROS users have easy access to Ignition Citadel, which is Ignition’s first 5-year LTS, to be supported until 2025.
Gazebo’s next generation
Ignition is the next generation of the Gazebo simulator, with an updated architecture and new features that are aimed at improving your simulation experience. Some of Ignition’s new features are:
- Plugin-based physics and rendering abstractions - use your own engines without recompiling the simulator
- Levels system, to only load the parts of the world that your robot is interacting with - which allows much larger simulation worlds
- Simulation distributed across several machines
- Highly customizable QtQuick-based user interface
- A super fast 2D kinematics physics engine, the Trivial Physics Engine (TPE)
On top of that, Ignition already has lots of the features that you’re used to from Gazebo-classic, such as:
- Separation of server and client for headless simulation
- Built-in support for several sensors, like cameras, lidars, IMUs, depth cameras, magnetometers, altimeters, air pressure sensors, etc.
- Animated human actors
- Plugins for robot control, such as differential drive and skid steer
- Graphical interfaces for manipulating models, introspecting properties, controlling view angles, inserting models, etc.
- ROS 1 and 2 integrations
Here’s a full feature comparison list.
Simulate
You can find the integration packages at GitHub - gazebosim/ros_gz: Integration between ROS (1 and 2) and Gazebo simulation. Try for example:
sudo apt install ros-foxy-ros-ign
. /opt/ros/foxy/setup.sh
ros2 launch ros_ign_gazebo_demos rgbd_camera_bridge.launch.py
More detailed tutorials on getting started using the simulator with ROS:
More demos:
And a video tutorial:
Libraries and tools
And there’s more! Ignition is more than a simulator: it is a collection of C++ libraries and tools that can be used independently of the simulator on your robot applications. You can use them on your ROS packages or plain C++ projects.
You can use these rosdep keys in your package.xml
ignition-citadel
ignition-cmake2
ignition-common3
ignition-fuel-tools4
ignition-gazebo3
ignition-gui3
ignition-launch2
ignition-math6
ignition-math6-eigen3
ignition-msgs5
ignition-physics2
ignition-plugin
ignition-rendering3
ignition-sensors3
ignition-tools
ignition-transport8
sdformat
The collection consists of 15 libraries. Here are some that you may find particularly interesting for your projects:
Ignition Math
Ignition Math is a general purpose math library for robot applications. It provides a wide range of functionality, including:
- Type-templated pose, matrix, vector, and quaternion classes.
- Shape representations along with operators to compute volume, density, size and other properties.
- Classes for material properties, mass, inertial, temperature, PID, kmeans, spherical coordinates, and filtering.
- Optional Eigen component that converts between a few Eigen and Ignition Math types.
Ignition Physics
Many physics simulation software libraries have been designed for different applications (gaming, robotics, science) and with different features (rigid or deformable contact, 2d or 3d). Ignition Physics is designed on the premise that there is not a single physics engine that is universally best for all simulation contexts. It should be possible to support a different set of features for each physics engine according to its capabilities. A physics engine can then be chosen for each application based on its context.
- Granular definition of physics engine features as optional API’s.
- Plugin interface for loading physics engines with requested features at runtime.
- Features for common aspects of rigid body dynamic simulation
- Construct model from SDFormat file.
- Collision shapes (such as box, sphere, cylinder, mesh, heightmap).
- Joint types (such as revolute, prismatic, fixed, ball, screw, universal).
- Step simulation, get/set state, apply inputs.
- Reference implementation of physics plugin using dartsim.
- CompositeData structures for efficiently using native types in API.
Ignition Rendering
Similar to Ignition Physics, Ignition Rendering is a C++ library designed to provide an abstraction for different rendering engines. It offers unified APIs for creating 3D graphics applications and supports Physically Based Rendering (PBR). It’s shipped with support for Ogre 1 and Ogre 2 engines.
Ignition GUI
Ignition GUI builds on top of Qt Quick to provide widgets with a modern material design look that are useful when developing robotics applications, such as 3D views, plots, dashboards, etc, and can be used together in a convenient unified interface.
Ignition GUI ships with several widgets ready to use and offers a plugin interface which can be used to add custom widgets.
Ignition Plugin
Ignition Plugin is a thin library for registering plugin libraries and dynamically loading them at runtime.
Ignition Common
Ignition Common provides a set of components that cover many different use cases. An audio-visual library supports processing audio and video files, a graphics library can load a variety 3D mesh file formats into a generic in-memory representation, and the core library of Ignition Common contains functionality that spans Base64 encoding/decoding to thread pools.
Some of the many capabilities contained in Ignition Common are:
- AV : FFMpeg based audio decoder, and video encoder and decoder.
- Core : Base64 encoding and decoding, battery model, console logging, cross-platform filesystem interface, URI processing, and a thread pool.
- Events : Mouse and keyboard events, and a high-performance signal and callback system.
- Graphics : Collada, SVG, STL, OBJ, and DEM loaders. In-memory mesh, image, and material representations. Animation processing and BVH loader.
- Profiler : A common profiler abstraction that can be used to measure and visualize the run time of various pieces of software.
Keep an eye on Gazebo Community for updates and discussions about new features.
Happy Simulating!
The Ignition Dev Team