Gazebo

Introduction

For simulation purposes with Gazebo simulator , Aerostack2 provides with a platform that serves as an entry point for aerial robotics simulated in this environment.

Installation

Prerequisites

Ignition Gazebo is required for simulation using this simulator. The default Gazebo version for working and simulating with Aerostack2 is Gazebo Fortress, which can be installed following the Gazebo Fortress installation guide.

Using ‘Gazebo Harmonic’

Gazebo Harmonic is also supported by Aerostack2. For simulations to work with this version, make sure Gazebo Fortress is completely removed from your machine, since both versions are not compatible with Aerostack2 at the same time. To do so, first run:

sudo apt-get remove ignition-fortress
sudo apt remove ignition*
sudo apt autoremove

To ensure no ignition-fortress packages are cached with the Aerostack2 compilation, run the following Aerostack2 CLI command to clean Aerostack2 if you have it compilled:

as2 clean -a
source ~/.bashrc

After that, you can follow the Gazebo Harmonic installation guide to install the new Gazebo version.

Warning

An additional package must be installed for Aerostack2 to build:

sudo apt install ros-humble-ros-gzharmonic

Note

Gazebo Fortress can be re-installed to your machine after Aerostack2 has been compiled with Gazebo Harmonic if you need it, but compiling Aerostack2 with Fortress again will not be possible.

Install platform package

  • For binary installation, install by running:

sudo apt install ros-humble-as2-platform-gazebo

Install simulation assets

  • For binary installation, install by running:

sudo apt install ros-humble-as2-gazebo-assets

Aerostack2 Common Interface

For more details about platform control modes and sensors, see Aerostack2 Aerial Platform Concepts. For more details, about bridge between Gazebo and ROS, see the Aerostack2 Gazebo ROS Bridge.

Control Modes

These are supported control modes:

Control Modes Gazebo Platform

Control Mode

Yaw Mode

Reference Frame

Hover

None

None

Speed

Speed

FLU

Sensors

These are supported sensors:

Sensors Gazebo Platform

Sensor

Topic

Type

IMU

sensor_measurements/imu

sensor_msgs/msg/Imu

Magnetometer

sensor_measurements/magnetic_field

sensor_msgs/msg/MagneticField

Air pressure

sensor_measurements/air_pressure

sensor_msgs/msg/FluidPressure

Battery

sensor_measurements/battery

sensor_msgs/msg/BatteryState

Camera

sensor_measurements/{model_name}/image_raw

sensor_msgs/msg/Image

Depth camera

sensor_measurements/{model_name}/depth

sensor_msgs/msg/Image

Camera

sensor_measurements/{model_name}/camera_info

sensor_msgs/msg/CameraInfo

Lidar

sensor_measurements/{model_name}/scan

sensor_msgs/msg/LaserScan

Lidar

sensor_measurements/{model_name}/points

sensor_msgs/msg/PointCloud2

Camera

sensor_measurements/{model_name}/points

sensor_msgs/msg/PointCloud2

Gimbal

Gimbal is supported in simulation. These are the supported gimbal model types:

Gimbal Control Modes Ignition Gazebo Platform

Gimbal type

Topic

Type

Control mode id

gimbal_position

platform/{gimbal_name}/gimbal_command

as2_msgs/msg/GimbalControl

“0”

gimbal_speed

platform/{gimbal_name}/gimbal_command

as2_msgs/msg/GimbalControl

“1”

Gimbal state is published in the following topics:

Gimbal State Ignition Gazebo Platform

Topic

Type

sensor_measurements/{gimbal_name}/twist

geometry_msgs/msg/Vector3Stamped

sensor_measurements/{gimbal_name}/attitude

geometry_msgs/msg/QuaternionStamped

Config Simulation

There are two aerial models available for simulation. These models are:

  • Quadrotor base.

../../_images/quadrotor.png

Quadrotor base model

  • Hexrotor base.

../../_images/hexrotor.png

Hexrotor base model

In order to add an aerial model with sensors attached to it to the simulated world, Aerostack2 uses a configuration file, with YAML format, with the following structure:

world_name: "empty"
drones:
  - model_name: "drone0"
    model_type: "quadrotor_base"
    xyz:
      - -2.0
      - 0.0
      - 0.3
    rpy:
      - 0
      - 0
      - 0.0
    flight_time: 60
    payload:
      - model_name: "hd_camera0"
        model_type: "hd_camera"
      - model_name: "gimbal0"
        model_type: "gimbal_position"
        payload:
          model_name: "hd_camera1"
          model_type: "hd_camera"

  - model_name: "drone1"
    model_type: "quadrotor_base"
    xyz:
      - 2.0
      - 0.0
      - 0.3
    rpy:
      - 0
      - 0
      - 0.0
    flight_time: 60
    payload:
      - model_name: "gimbal1"
        model_type: "gimbal_speed"
        payload:
          model_name: "hd_camera1"
          model_type: "hd_camera"

  - model_name: "drone2"
    model_type: "quadrotor_base"
    xyz:
      - 0.0
      - 0.0
      - 0.3
    rpy:
      - 0
      - 0
      - 0.0
    flight_time: 60
    payload:
      - model_name: "hd_camera2"
        model_type: "hd_camera"

Where:

  • world_name: name of the defined world in sdf format.

  • drones: list of drones to be included in the world.

Each of the drones is defined by:

  • model_type: model of the drone defined in sdf format.

  • model_name: namespace

  • xyz: spawn position

  • rpy: spawn orientation

  • payload: list of sensors/gimbal attached to the model

Each element of the payload is defined by:

  • model_type: name of the sensor/gimbal inside the simulation (this case gps and gimbal_speed)

  • model_name: name of the sensor/gimbal defined in sdf format.

If a drone payload contains a gimbal, a gimbal should contain a payload which must containt a sensor.

New models, sensors and worlds are defined in the as2_gazebo_assets package. For more information on how to create new assets, go to the Adding New Gazebo Assets tutorial or to the Develop Guide section for Creating New Gazebo Assets.

Platform Launch

Aerostack2 Gazebo platform provides a launch file, which parameters are:

Gazebo Platform Parameters

Parameter

Type

Description

namespace

string

Namespace of the platform, also named as drone id.

simulation_config_file

string

Path to the simulation configuration file.

control_modes_file

string

Optional. File path with the control modes configuration. Default the one in the package.

platform_config_file

string

Optional. File path with additional platform parameters.

log_level

string

Optional. Set Logging level. Default ‘info’.

use_sim_time

bool

Optional. Syncronize simulation time with node time. Default false.

Aerostack2 provides a launch file for this platform:

ros2 launch as2_platform_gazebo platform_gazebo_launch.py namespace:=drone_sim_0 simulation_config_file:=world_json_path

For launch the simulation, run the following command:

ros2 launch as2_gazebo_assets launch_simulation.py simulation_config_file:=world_json_path

To see all the available parameters, use the ‘-s’ flag to show the description of each parameter in the launch file.

Additionally, for launching teleoperation and trying out a basic mission, continue to the Gazebo Example Project.