E2ES icon indicating copy to clipboard operation
E2ES copied to clipboard

A complete MAV simulation on Gazebo

E2ES

End-to-End UAV Simulation for Visual SLAM and Navigation

Introduction

This Kit provides an end to end simulation solution for MAV visual SLAM (or path planning) researches.
In this work, several features are added to the default PX4 Gazebo Simulator:
-A realsense D435 model (based on realsense_gazebo_plugin)
-Modified IRIS MAV model
-Several structured/unstructured simulation world

The work has been verified on Ubuntu 18.04/20.04 + ROS melodic/noetic environment
Also, if you want to save time, we strongly suggest you to use docker image! The link is right here.

Demo Video

cla

manual control Click and fly navigation

Main Functions

We include 3 main functionalities to users:

  • Mapping environments for path planning and SLAM works.
  • A single drone environment for controller design. Disturbances can be added.
  • A team of 3 drones for swarm applications.

Usage

If you still insist not to use docker, follow this to do the installation.

Run the simulator

roscd e2es
./sim.sh map # for mapping environment and camera
./sim.sh single # for control testing, only 1 drone will be spawned
./sim.sh swarm # for control testing, 3 drones will be spawned

Using keyboard to control the MAV in simulator

roslaunch e2es keyboard_ctr.launch

You can also add disturbances to the environemnt via

roslaunch e2es disturb.launch

More on End-To-End simulation

1. SLAM

A.

You can use the FLVIS + MLMapping kit combination to run SLAM. Please refer to the respective repo, FLVIS & MLMap to build them. Also make sure that you safisfy their prerequisites.

The launch file for E2ES are here_FLVIS & here_MAP. Hence, do

roslaunch flvis e2es.launch # for VIO
roslaunch mlmapping mlmapping_e2es.launch # for Mapping
B.

The topics there you might be interested are as follows:

Topic Topic Type Topic Name Hz
Pose (GT) geometry_msgs/PoseStamped /gt_iris_base_link_imu 50
Pose (VIO) geometry_msgs/PoseStamped /mavros/vision_pose/pose 200
Odom (VIO) nav_msgs/Odometry /imu_odom 200
IMU (PX4) sensor_msgs/IMU /mavros/imu/data 50
IMU (Gazebo) sensor_msgs/IMU /iris/imu/data 200
RAW PCL sensor_msgs/Image /camera/depth_aligned_to_color_and_infra1/image_raw 30
MAP sensor_msgs/PointCloud2 /global_map 20

You can modify the launch file, and

2. Autonomous Navigation (deprecated)

You can use the FLVIS-glmapping-FUXI(localization-mapping-planning kits) navigation system.
The first step is to install FLVIS, glmapping and FUXI accordinly.
Then start the simulator localization mapping and planning kit in sequence.

roscd e2es
./sim.sh

# flvis
roslaunch flvis e2es.launch # under flvis package

# fuxi
## please refer to fuxi repo

Acknowledgement

This work are based on PX4 Projcet and realsense_gazebo_plugin

Maintainer

Patrick Lo, AIRo-Lab, RCUAS, PolyU
Shengyang Chen, Dept.ME, PolyU