ardrone_autonomy

Summary

ardrone_autonomy
Version:

1.4.1

Description:

ardrone_autonomy is a ROS driver for Parrot AR-Drone 1.0 and 2.0 quadrocopters. This driver is based on official AR-Drone SDK version 2.0.1.

Maintainers:
  • Mani Monajjemi <mmonajje AT sfu DOT ca>
Licenses:
  • BSD
Urls:
Authors:
  • Mani Monajjemi
  • Mani Monajjemi
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:
Exports:
  • <rosdoc config=”rosdoc.yaml”/>

Types

Message types

ardrone_autonomy/navdata_watchdog
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
Header header
float64 drone_time
uint16 tag
uint16 size
ardrone_autonomy/matrix33
Field:
  • m11 (float32) –
  • m12 (float32) –
  • m13 (float32) –
  • m21 (float32) –
  • m22 (float32) –
  • m23 (float32) –
  • m31 (float32) –
  • m32 (float32) –
  • m33 (float32) –
float32 m11
float32 m12
float32 m13
float32 m21
float32 m22
float32 m23
float32 m31
float32 m32
float32 m33
ardrone_autonomy/Navdata
Field:
  • header (std_msgs/Header) –
  • batteryPercent (float32) –
  • state (uint32) –
  • magX (int32) –
  • magY (int32) –
  • magZ (int32) –
  • pressure (int32) –
  • temp (int32) –
  • wind_speed (float32) –
  • wind_angle (float32) –
  • wind_comp_angle (float32) –
  • rotX (float32) –
  • rotY (float32) –
  • rotZ (float32) –
  • altd (int32) –
  • vx (float32) –
  • vy (float32) –
  • vz (float32) –
  • ax (float32) –
  • ay (float32) –
  • az (float32) –
  • motor1 (uint8) –
  • motor2 (uint8) –
  • motor3 (uint8) –
  • motor4 (uint8) –
  • tags_count (uint32) –
  • tags_type[] (uint32) –
  • tags_xc[] (uint32) –
  • tags_yc[] (uint32) –
  • tags_width[] (uint32) –
  • tags_height[] (uint32) –
  • tags_orientation[] (float32) –
  • tags_distance[] (float32) –
  • tm (float32) –
Header header

# Navdata including the ARDrone 2 specifica sensors
# (magnetometer, barometer)

# 0 means no battery, 100 means full battery
float32 batteryPercent

# 0: Unknown, 1: Init, 2: Landed, 3: Flying, 4: Hovering, 5: Test
# 6: Taking off, 7: Goto Fix Point, 8: Landing, 9: Looping
# Note: 3,7 seems to discriminate type of flying (isFly = 3 | 7)
uint32 state

int32 magX
int32 magY
int32 magZ

# pressure sensor
int32 pressure

# apparently, there was a temperature sensor added as well.
int32 temp

# wind sensing...
float32 wind_speed
float32 wind_angle
float32 wind_comp_angle

# left/right tilt in degrees (rotation about the X axis)
float32 rotX

# forward/backward tilt in degrees (rotation about the Y axis)
float32 rotY

# orientation in degrees (rotation about the Z axis)
float32 rotZ

# estimated altitude (cm)
int32 altd

# linear velocity (mm/sec)
float32 vx

# linear velocity (mm/sec)
float32 vy

# linear velocity (mm/sec)
float32 vz

#linear accelerations (unit: g)
float32 ax
float32 ay
float32 az

#motor commands (unit 0 to 255)
uint8 motor1
uint8 motor2
uint8 motor3
uint8 motor4

#Tags in Vision Detectoion
uint32 tags_count
uint32[] tags_type
uint32[] tags_xc
uint32[] tags_yc
uint32[] tags_width
uint32[] tags_height
float32[] tags_orientation
float32[] tags_distance

#time stamp
float32 tm
ardrone_autonomy/navdata_hdvideo_stream
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • hdvideo_state (uint32) –
  • storage_fifo_nb_packets (uint32) –
  • storage_fifo_size (uint32) –
  • usbkey_size (uint32) –
  • usbkey_freespace (uint32) –
  • frame_number (uint32) –
  • usbkey_remaining_time (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 hdvideo_state
uint32 storage_fifo_nb_packets
uint32 storage_fifo_size
uint32 usbkey_size
uint32 usbkey_freespace
uint32 frame_number
uint32 usbkey_remaining_time
ardrone_autonomy/navdata_raw_measures
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • raw_gyros[] (int16) –
  • raw_gyros_110[] (int16) –
  • vbat_raw (uint32) –
  • us_debut_echo (uint16) –
  • us_fin_echo (uint16) –
  • us_association_echo (uint16) –
  • us_distance_echo (uint16) –
  • us_courbe_temps (uint16) –
  • us_courbe_valeur (uint16) –
  • us_courbe_ref (uint16) –
  • flag_echo_ini (uint16) –
  • nb_echo (uint16) –
  • sum_echo (uint32) –
  • alt_temp_raw (int32) –
  • gradient (int16) –
Header header
float64 drone_time
uint16 tag
uint16 size
int16[] raw_gyros
int16[] raw_gyros_110
uint32 vbat_raw
uint16 us_debut_echo
uint16 us_fin_echo
uint16 us_association_echo
uint16 us_distance_echo
uint16 us_courbe_temps
uint16 us_courbe_valeur
uint16 us_courbe_ref
uint16 flag_echo_ini
uint16 nb_echo
uint32 sum_echo
int32 alt_temp_raw
int16 gradient
ardrone_autonomy/navdata_time
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • time (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 time
ardrone_autonomy/navdata_gyros_offsets
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • offset_g[] (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32[] offset_g
ardrone_autonomy/navdata_kalman_pressure
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • offset_pressure (float32) –
  • est_z (float32) –
  • est_zdot (float32) –
  • est_bias_PWM (float32) –
  • est_biais_pression (float32) –
  • offset_US (float32) –
  • prediction_US (float32) –
  • cov_alt (float32) –
  • cov_PWM (float32) –
  • cov_vitesse (float32) –
  • bool_effet_sol (int32) –
  • somme_inno (float32) –
  • flag_rejet_US (int32) –
  • u_multisinus (float32) –
  • gaz_altitude (float32) –
  • Flag_multisinus (int32) –
  • Flag_multisinus_debut (int32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32 offset_pressure
float32 est_z
float32 est_zdot
float32 est_bias_PWM
float32 est_biais_pression
float32 offset_US
float32 prediction_US
float32 cov_alt
float32 cov_PWM
float32 cov_vitesse
int32 bool_effet_sol
float32 somme_inno
int32 flag_rejet_US
float32 u_multisinus
float32 gaz_altitude
int32 Flag_multisinus
int32 Flag_multisinus_debut
ardrone_autonomy/navdata_demo
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • ctrl_state (uint32) –
  • vbat_flying_percentage (uint32) –
  • theta (float32) –
  • phi (float32) –
  • psi (float32) –
  • altitude (int32) –
  • vx (float32) –
  • vy (float32) –
  • vz (float32) –
  • num_frames (uint32) –
  • detection_camera_type (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 ctrl_state
uint32 vbat_flying_percentage
float32 theta
float32 phi
float32 psi
int32 altitude
float32 vx
float32 vy
float32 vz
uint32 num_frames
uint32 detection_camera_type
ardrone_autonomy/navdata_zimmu_3000
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • vzimmuLSB (int32) –
  • vzfind (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
int32 vzimmuLSB
float32 vzfind
ardrone_autonomy/navdata_vision_of
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • of_dx[] (float32) –
  • of_dy[] (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32[] of_dx
float32[] of_dy
ardrone_autonomy/navdata_altitude
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • altitude_vision (int32) –
  • altitude_vz (float32) –
  • altitude_ref (int32) –
  • altitude_raw (int32) –
  • obs_accZ (float32) –
  • obs_alt (float32) –
  • obs_x (ardrone_autonomy/vector31) –
  • obs_state (uint32) –
  • est_vb (ardrone_autonomy/vector21) –
  • est_state (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
int32 altitude_vision
float32 altitude_vz
int32 altitude_ref
int32 altitude_raw
float32 obs_accZ
float32 obs_alt
vector31 obs_x
uint32 obs_state
vector21 est_vb
uint32 est_state
ardrone_autonomy/navdata_references
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • ref_theta (int32) –
  • ref_phi (int32) –
  • ref_theta_I (int32) –
  • ref_phi_I (int32) –
  • ref_pitch (int32) –
  • ref_roll (int32) –
  • ref_yaw (int32) –
  • ref_psi (int32) –
  • vx_ref (float32) –
  • vy_ref (float32) –
  • theta_mod (float32) –
  • phi_mod (float32) –
  • k_v_x (float32) –
  • k_v_y (float32) –
  • k_mode (uint32) –
  • ui_time (float32) –
  • ui_theta (float32) –
  • ui_phi (float32) –
  • ui_psi (float32) –
  • ui_psi_accuracy (float32) –
  • ui_seq (int32) –
Header header
float64 drone_time
uint16 tag
uint16 size
int32 ref_theta
int32 ref_phi
int32 ref_theta_I
int32 ref_phi_I
int32 ref_pitch
int32 ref_roll
int32 ref_yaw
int32 ref_psi
float32 vx_ref
float32 vy_ref
float32 theta_mod
float32 phi_mod
float32 k_v_x
float32 k_v_y
uint32 k_mode
float32 ui_time
float32 ui_theta
float32 ui_phi
float32 ui_psi
float32 ui_psi_accuracy
int32 ui_seq
ardrone_autonomy/navdata_games
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • double_tap_counter (uint32) –
  • finish_line_counter (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 double_tap_counter
uint32 finish_line_counter
ardrone_autonomy/navdata_pwm
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • motor1 (uint8) –
  • motor2 (uint8) –
  • motor3 (uint8) –
  • motor4 (uint8) –
  • sat_motor1 (uint8) –
  • sat_motor2 (uint8) –
  • sat_motor3 (uint8) –
  • sat_motor4 (uint8) –
  • gaz_feed_forward (float32) –
  • gaz_altitude (float32) –
  • altitude_integral (float32) –
  • vz_ref (float32) –
  • u_pitch (int32) –
  • u_roll (int32) –
  • u_yaw (int32) –
  • yaw_u_I (float32) –
  • u_pitch_planif (int32) –
  • u_roll_planif (int32) –
  • u_yaw_planif (int32) –
  • u_gaz_planif (float32) –
  • current_motor1 (uint16) –
  • current_motor2 (uint16) –
  • current_motor3 (uint16) –
  • current_motor4 (uint16) –
  • altitude_der (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint8 motor1
uint8 motor2
uint8 motor3
uint8 motor4
uint8 sat_motor1
uint8 sat_motor2
uint8 sat_motor3
uint8 sat_motor4
float32 gaz_feed_forward
float32 gaz_altitude
float32 altitude_integral
float32 vz_ref
int32 u_pitch
int32 u_roll
int32 u_yaw
float32 yaw_u_I
int32 u_pitch_planif
int32 u_roll_planif
int32 u_yaw_planif
float32 u_gaz_planif
uint16 current_motor1
uint16 current_motor2
uint16 current_motor3
uint16 current_motor4
float32 altitude_der
ardrone_autonomy/navdata_video_stream
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • quant (uint8) –
  • frame_size (uint32) –
  • frame_number (uint32) –
  • atcmd_ref_seq (uint32) –
  • atcmd_mean_ref_gap (uint32) –
  • atcmd_var_ref_gap (float32) –
  • atcmd_ref_quality (uint32) –
  • desired_bitrate (uint32) –
  • data2 (int32) –
  • data3 (int32) –
  • data4 (int32) –
  • data5 (int32) –
  • fifo_queue_level (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint8 quant
uint32 frame_size
uint32 frame_number
uint32 atcmd_ref_seq
uint32 atcmd_mean_ref_gap
float32 atcmd_var_ref_gap
uint32 atcmd_ref_quality
uint32 desired_bitrate
int32 data2
int32 data3
int32 data4
int32 data5
uint32 fifo_queue_level
ardrone_autonomy/navdata_trims
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • angular_rates_trim_r (float32) –
  • euler_angles_trim_theta (float32) –
  • euler_angles_trim_phi (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32 angular_rates_trim_r
float32 euler_angles_trim_theta
float32 euler_angles_trim_phi
ardrone_autonomy/navdata_magneto
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • mx (int16) –
  • my (int16) –
  • mz (int16) –
  • magneto_raw (ardrone_autonomy/vector31) –
  • magneto_rectified (ardrone_autonomy/vector31) –
  • magneto_offset (ardrone_autonomy/vector31) –
  • heading_unwrapped (float32) –
  • heading_gyro_unwrapped (float32) –
  • heading_fusion_unwrapped (float32) –
  • magneto_calibration_ok (uint8) –
  • magneto_state (uint32) –
  • magneto_radius (float32) –
  • error_mean (float32) –
  • error_var (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
int16 mx
int16 my
int16 mz
vector31 magneto_raw
vector31 magneto_rectified
vector31 magneto_offset
float32 heading_unwrapped
float32 heading_gyro_unwrapped
float32 heading_fusion_unwrapped
uint8 magneto_calibration_ok
uint32 magneto_state
float32 magneto_radius
float32 error_mean
float32 error_var
ardrone_autonomy/navdata_wind_speed
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • wind_speed (float32) –
  • wind_angle (float32) –
  • wind_compensation_theta (float32) –
  • wind_compensation_phi (float32) –
  • state_x1 (float32) –
  • state_x2 (float32) –
  • state_x3 (float32) –
  • state_x4 (float32) –
  • state_x5 (float32) –
  • state_x6 (float32) –
  • magneto_debug1 (float32) –
  • magneto_debug2 (float32) –
  • magneto_debug3 (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32 wind_speed
float32 wind_angle
float32 wind_compensation_theta
float32 wind_compensation_phi
float32 state_x1
float32 state_x2
float32 state_x3
float32 state_x4
float32 state_x5
float32 state_x6
float32 magneto_debug1
float32 magneto_debug2
float32 magneto_debug3
ardrone_autonomy/navdata_vision_detect
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • nb_detected (uint32) –
  • type[] (uint32) –
  • xc[] (uint32) –
  • yc[] (uint32) –
  • width[] (uint32) –
  • height[] (uint32) –
  • dist[] (uint32) –
  • orientation_angle[] (float32) –
  • rotation[] (ardrone_autonomy/matrix33) –
  • translation[] (ardrone_autonomy/vector31) –
  • camera_source[] (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 nb_detected
uint32[] type
uint32[] xc
uint32[] yc
uint32[] width
uint32[] height
uint32[] dist
float32[] orientation_angle
matrix33[] rotation
vector31[] translation
uint32[] camera_source
ardrone_autonomy/navdata_rc_references
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • rc_ref_pitch (int32) –
  • rc_ref_roll (int32) –
  • rc_ref_yaw (int32) –
  • rc_ref_gaz (int32) –
  • rc_ref_ag (int32) –
Header header
float64 drone_time
uint16 tag
uint16 size
int32 rc_ref_pitch
int32 rc_ref_roll
int32 rc_ref_yaw
int32 rc_ref_gaz
int32 rc_ref_ag
ardrone_autonomy/navdata_adc_data_frame
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • version (uint32) –
  • data_frame[] (uint8) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 version
uint8[] data_frame
ardrone_autonomy/navdata_trackers_send
Field:
Header header
float64 drone_time
uint16 tag
uint16 size
int32[] locked
vector21[] point
ardrone_autonomy/navdata_vision_perf
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • time_corners (float32) –
  • time_compute (float32) –
  • time_tracking (float32) –
  • time_trans (float32) –
  • time_update (float32) –
  • time_custom[] (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32 time_corners
float32 time_compute
float32 time_tracking
float32 time_trans
float32 time_update
float32[] time_custom
ardrone_autonomy/navdata_pressure_raw
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • up (int32) –
  • ut (int16) –
  • Temperature_meas (int32) –
  • Pression_meas (int32) –
Header header
float64 drone_time
uint16 tag
uint16 size
int32 up
int16 ut
int32 Temperature_meas
int32 Pression_meas
ardrone_autonomy/navdata_wifi
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • link_quality (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 link_quality
ardrone_autonomy/navdata_vision_raw
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • vision_tx_raw (float32) –
  • vision_ty_raw (float32) –
  • vision_tz_raw (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32 vision_tx_raw
float32 vision_ty_raw
float32 vision_tz_raw
ardrone_autonomy/navdata_euler_angles
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • theta_a (float32) –
  • phi_a (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32 theta_a
float32 phi_a
ardrone_autonomy/vector31
Field:
  • x (float32) –
  • y (float32) –
  • z (float32) –
float32 x
float32 y
float32 z
ardrone_autonomy/navdata_vision
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • vision_state (uint32) –
  • vision_misc (int32) –
  • vision_phi_trim (float32) –
  • vision_phi_ref_prop (float32) –
  • vision_theta_trim (float32) –
  • vision_theta_ref_prop (float32) –
  • new_raw_picture (int32) –
  • theta_capture (float32) –
  • phi_capture (float32) –
  • psi_capture (float32) –
  • altitude_capture (int32) –
  • time_capture (uint32) –
  • body_v (ardrone_autonomy/vector31) –
  • delta_phi (float32) –
  • delta_theta (float32) –
  • delta_psi (float32) –
  • gold_defined (uint32) –
  • gold_reset (uint32) –
  • gold_x (float32) –
  • gold_y (float32) –
Header header
float64 drone_time
uint16 tag
uint16 size
uint32 vision_state
int32 vision_misc
float32 vision_phi_trim
float32 vision_phi_ref_prop
float32 vision_theta_trim
float32 vision_theta_ref_prop
int32 new_raw_picture
float32 theta_capture
float32 phi_capture
float32 psi_capture
int32 altitude_capture
uint32 time_capture
vector31 body_v
float32 delta_phi
float32 delta_theta
float32 delta_psi
uint32 gold_defined
uint32 gold_reset
float32 gold_x
float32 gold_y
ardrone_autonomy/navdata_phys_measures
Field:
  • header (std_msgs/Header) –
  • drone_time (float64) –
  • tag (uint16) –
  • size (uint16) –
  • accs_temp (float32) –
  • gyro_temp (uint16) –
  • phys_accs[] (float32) –
  • phys_gyros[] (float32) –
  • alim3V3 (uint32) –
  • vrefEpson (uint32) –
  • vrefIDG (uint32) –
Header header
float64 drone_time
uint16 tag
uint16 size
float32 accs_temp
uint16 gyro_temp
float32[] phys_accs
float32[] phys_gyros
uint32 alim3V3
uint32 vrefEpson
uint32 vrefIDG
ardrone_autonomy/vector21
Field:
  • x (float32) –
  • y (float32) –
float32 x
float32 y

Service types

ardrone_autonomy/RecordEnable
Field (Request):
 
  • enable (bool) –
Field (Response):
 
  • result (bool) –
bool enable
---
bool result
ardrone_autonomy/FlightAnim
Field (Request):
 
  • type (uint8) –
  • duration (uint32) –
Field (Response):
 
  • result (bool) –

0 : ARDRONE_ANIM_PHI_M30_DEG 1 : ARDRONE_ANIM_PHI_30_DEG 2 : ARDRONE_ANIM_THETA_M30_DEG 3 : ARDRONE_ANIM_THETA_30_DEG 4 : ARDRONE_ANIM_THETA_20DEG_YAW_200DEG 5 : ARDRONE_ANIM_THETA_20DEG_YAW_M200DEG 6 : ARDRONE_ANIM_TURNAROUND 7 : ARDRONE_ANIM_TURNAROUND_GODOWN 8 : ARDRONE_ANIM_YAW_SHAKE 9 : ARDRONE_ANIM_YAW_DANCE 10: ARDRONE_ANIM_PHI_DANCE 11: ARDRONE_ANIM_THETA_DANCE 12: ARDRONE_ANIM_VZ_DANCE 13: ARDRONE_ANIM_WAVE 14: ARDRONE_ANIM_PHI_THETA_MIXED 15: ARDRONE_ANIM_DOUBLE_PHI_THETA_MIXED 16: ARDRONE_ANIM_FLIP_AHEAD 17: ARDRONE_ANIM_FLIP_BEHIND 18: ARDRONE_ANIM_FLIP_LEFT 19: ARDRONE_ANIM_FLIP_RIGHT

# 0 : ARDRONE_ANIM_PHI_M30_DEG
# 1 : ARDRONE_ANIM_PHI_30_DEG
# 2 : ARDRONE_ANIM_THETA_M30_DEG
# 3 : ARDRONE_ANIM_THETA_30_DEG
# 4 : ARDRONE_ANIM_THETA_20DEG_YAW_200DEG
# 5 : ARDRONE_ANIM_THETA_20DEG_YAW_M200DEG
# 6 : ARDRONE_ANIM_TURNAROUND
# 7 : ARDRONE_ANIM_TURNAROUND_GODOWN
# 8 : ARDRONE_ANIM_YAW_SHAKE
# 9 : ARDRONE_ANIM_YAW_DANCE
# 10: ARDRONE_ANIM_PHI_DANCE
# 11: ARDRONE_ANIM_THETA_DANCE
# 12: ARDRONE_ANIM_VZ_DANCE
# 13: ARDRONE_ANIM_WAVE
# 14: ARDRONE_ANIM_PHI_THETA_MIXED
# 15: ARDRONE_ANIM_DOUBLE_PHI_THETA_MIXED
# 16: ARDRONE_ANIM_FLIP_AHEAD
# 17: ARDRONE_ANIM_FLIP_BEHIND
# 18: ARDRONE_ANIM_FLIP_LEFT
# 19: ARDRONE_ANIM_FLIP_RIGHT

uint8 type

# In Milliseconds
# 0 For Default Duration (Recommended)
uint32 duration

---
bool result
ardrone_autonomy/CamSelect
Field (Request):
 
  • channel (uint8) –
Field (Response):
 
  • result (bool) –
uint8 channel
---
bool result
ardrone_autonomy/LedAnim
Field (Request):
 
  • type (uint8) –
  • freq (float32) –
  • duration (uint8) –
Field (Response):
 
  • result (bool) –

0 : BLINK_GREEN_RED 1 : BLINK_GREEN 2 : BLINK_RED 3 : BLINK_ORANGE 4 : SNAKE_GREEN_RED 5 : FIRE 6 : STANDARD 7 : RED 8 : GREEN 9 : RED_SNAKE 10: BLANK 11: LEFT_GREEN_RIGHT_RED 12: LEFT_RED_RIGHT_GREEN 13: BLINK_STANDARD

# 0 : BLINK_GREEN_RED
# 1 : BLINK_GREEN
# 2 : BLINK_RED
# 3 : BLINK_ORANGE
# 4 : SNAKE_GREEN_RED
# 5 : FIRE
# 6 : STANDARD
# 7 : RED
# 8 : GREEN
# 9 : RED_SNAKE
# 10: BLANK
# 11: LEFT_GREEN_RIGHT_RED
# 12: LEFT_RED_RIGHT_GREEN
# 13: BLINK_STANDARD
uint8 type

# In Hz
float32 freq

# In Seconds
uint8 duration 

---
bool result