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 outdoor flight demo
Description: This tutorial describes how to simulate a quadrotor UAV flying in a outdoor scenario using the hector_quadrotor stack.Tutorial Level: INTERMEDIATE
Next Tutorial: Quadrotor indoor SLAM demo hector_quadrotor/Tutorials/Quadrotor indoor SLAM demo
Contents
Overview
This tutorial describes the setup and launch of the outdoor flight scenario shown in the video below. The quadrotor UAV is teleoperated.
Setup
Prerequisites
Install binary packages
The hector_quadrotor, 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 outdoor flight demo:
roslaunch hector_quadrotor_demo outdoor_flight_gazebo.launch
gazebo simulation as well as rviz visualization should start up now, and the quadrotor UAV should be on the ground ready for takeoff.
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.
GPS
The quadrotor aircraft uses ground truth information from gazebo for localization in this scenario, simulating the availability of GPS signals in outdoor scenarios. In this example, there is no artifical noise added.