(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Quadrotor indoor SLAM demo

Description: This tutorial describes how to simulate a quadrotor UAV performing indoor SLAM using the hector_quadrotor stack.

Tutorial Level: BEGINNER

Overview

This tutorial describes the setup and launch of the indoor SLAM scenario shown in the video below. The quadrotor UAV is teleoperated here and hector_slam is used for learning a map of the environment.

Setup

Prerequisites

Install binary packages

The hector_quadrotor, hector_slam, hector_localization, hector_gazebo and hector_models packages are needed to run this demo.

The simplest option is to install the Ubuntu binary packages of hector_quadrotor available in the ROS package repository. To install all required packages for this tutorial run:

sudo apt-get install ros-hydro-hector-quadrotor-demo

Install from source

Alternatively, if you want to build from source in order to edit source or configuration files to suit your needs, all required stacks can be installed with the following commands (requires wstool):

mkdir ~/hector_quadrotor_tutorial
cd ~/hector_quadrotor_tutorial
wstool init src https://raw.github.com/tu-darmstadt-ros-pkg/hector_quadrotor/hydro-devel/tutorials.rosinstall

Build the catkin workspace as usual and source the new setup.bash:

catkin_make
source devel/setup.bash

Launch

Launch the indoor SLAM demo:

roslaunch hector_quadrotor_demo indoor_slam_gazebo.launch

gazebo simulation as well as rviz visualization should start up now, and the quadrotor UAV should be on the ground.

Control

Control

Depending on the version of the package you use, you might have to enable motors via a service first:

rosservice call /enable_motors "enable: true"

The quadrotor accepts geometry_msgs/Twist messages on the 'cmd_vel' topic, as many other robots do, too. It is recommended to use a gamepad for teleoperation. For this, start the appropriate launch file of the hector_quadrotor_teleop package, in case of an Xbox controller:

roslaunch hector_quadrotor_teleop xbox_controller.launch 

You can also control the UAV using any other method for publishing geometry_msgs/Twist messages. This of course also includes controllers for autonomous flight. If you have installed the teleop_twist_keyboard package, you can for example also use this:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py

Demo

Camera

You can activate the view of the onboard camera by ticking the corresponding entry in rviz (left pane). For teleoperation using the camera, it is recommended to untick the tf and robot_model visualizations as they might block the view occasionally.

SLAM

SLAM is performed using the hector_mapping package from the hector_slam stack. Note that the attitude estimate comes from gazebo, but 2D localization and mapping do not use ground truth information. This can also be verified by flying too high, which leads to SLAM failure. The 3D robot trajectory is tracked and visualized in rviz using the hector_trajectory_server package. A map including the trajectory can be saved to a GeoTiff file using

rostopic pub syscommand std_msgs/String "savegeotiff"

The saved map can be found in the 'hector_geotiff/map' directory.

Wiki: hector_quadrotor/Tutorials/Quadrotor indoor SLAM demo (last edited 2018-03-15 08:59:08 by StefanKohlbrecher)