Usage

Be sure that the AR.Drone has completed it's boot sequence (indicated by a green LED on the bottom), and that it is connected to your computer via WiFi. Also, make sure you have plenty of room to safely fly the AR.Drone. When using the AR.Drone, keep in mind the range of WiFi, and the range of bluetooth.

If the AR.Drone does not receive a command for more than 250 ms, it will enter hovering mode and remain in place. It will then wait for up to two minutes for a re-connection, at which point an automatic landing will occur.

ardrone_driver will maintain the connection automatically by sending a specific packet approximately every 200ms.

To bring the driver online:

rosrun ardrone_driver ardrone_driver

Controlling the AR.Drone

A geometry_msgs/Twist is used to control the velocity of the AR.Drone. Four parameters of the message are currently used. All values should be specified between 1 and -1. For the smoothest possible movement, a geometry_msgs/Twist should be published at a rate of no less than 30Hz.

Movement is specified in meters per second. Maximum value specified should be no more than 0.8. For maximum stability while flying, a value of .5 or lower is suggested.
  • linear.x - (+)forward and (-)backward
  • linear.y - (+)left and (-)right
  • linear.z - (+)up and (-)down

Rotation is specified in radians per second.
  • angular.z - The rotational velocity. Causes rotation about the center.

Nodes

ardrone_driver

Provides a control interface to the AR.Drone

Subscribed Topics

cmd_vel (geometry_msgs/Twist)

Published Topics

/ardrone/imu/data (sensor_msgs/Imu)
  • Imu data from the on-board sensors.
/ardrone/imu/is_calibrated (std_msgs/Bool)
  • Indicates that the on-board IMU has been zeroed. This happens automatically at takeoff, and can be done manually with a service call.
/ardrone/state (ardrone_driver/ARDroneState)
  • Information about the current state, including battery level and altitude. Also indicates if the AR.Drone is currently airborne.

Services

/ardrone/takeoff (ardrone/Takeoff)
  • Causes the AR.Drone to takeoff
/ardrone/land (ardrone/Land)
  • Causes the AR.Drone to land
/ardrone/reset (ardrone/Reset)
  • Toggles the emergency reset flag on the AR.Drone. This can be used as both an emergency kill switch, and a reset command for an AR.Drone that is in emergency stop mode
/ardrone/imu/calibrate (std_srvs/Empty)
  • Calibrates the on-board IMU. Use only while landed on flat ground.

Parameters

drone_ip (string, default: "192.168.1.1")
  • IP of the AR.Drone
drone_port (int, default: 5556)
  • Port for AR.Drone commands
tilt_max (double, default: .44)
  • Maximum tilt angle for the AR.Drone. Not to exceed .52 radians. It is highly recommended that users keep this set to the default value.
altitude_max (double, default: 1)
  • Altitude limit for the AR.Drone, in meters. 10 = unlimited.

Wiki: ardrone_driver (last edited 2010-10-21 17:51:54 by NateRoney)