1 /******************************************************************************
2 * COPYRIGHT PARROT 2010
3 ******************************************************************************
5 *---------------------------------------------------------------------------*/
8 * @brief Data types and functions to communicate with the drone.
10 ******************************************************************************/
12 #ifndef _ARDRONE_API_H_
13 #define _ARDRONE_API_H_
15 /*--- Libraries --------------------------------------------------------------*/
17 #include <ardrone_common_config.h>
18 #include <ATcodec/ATcodec_api.h>
19 #include <navdata_common.h>
20 #include <vision_common.h>
21 #include <VP_Os/vp_os_malloc.h>
22 #include <Maths/quaternions.h>
25 * @brief Defines the API_WEAK attribute.
26 * It is used to define a function which
27 * can be redefined by the SDK user with a custom one, without generating
28 * a 'multiple definition' compilation error. This is a GCC specific feature.
30 #if defined(USE_LINUX) && defined(_EMBEDDED) && !defined(USE_MINGW32)
36 /** @def ARDRONE_CONFIGURATION_SET
37 * @brief Sets a drone configuration value.
38 * This is the main method that SDK users should use to change a setting on
40 * @def ARDRONE_CONFIGURATION_SET_FUNCTION
41 * @brief Used internally by ARDroneLib to build the name of a function
42 * changing a particular drone configuration value.
43 * @def ARDRONE_CONFIGURATION_PROTOTYPE
44 * @brief Used internally by ARDroneLib to define a function changing a
45 * particular drone configuration value.
47 //Deprecated - no ack method - #define ARDRONE_CONFIGURATION_SET(NAME, VALUE) ARDRONE_CONFIGURATION_SET_FUNCTION(NAME)(VALUE)
48 #define ARDRONE_CONFIGURATION_SET_FUNCTION(NAME) ardrone_at_configuration_set_##NAME
49 #define ARDRONE_CONFIGURATION_PROTOTYPE(NAME) C_RESULT ARDRONE_CONFIGURATION_SET_FUNCTION(NAME)(void* value, char* ses_id, char* usr_id, char* app_id)
52 * @brief Used internally by ARDroneTool as an argument to the creation of
53 * a control event, when changing a configuration value.
54 * SDK users should not deal with this; see ARDRONE_CONFIGURATION_SET to change
58 typedef C_RESULT (*ardrone_at_configuration_set)(void* value, char* ses_id, char* usr_id, char* app_id);
61 * @brief Used internally by ARDroneTool as argument to the miscellaneous
62 * settings (see AT*MISC command).
68 ALTITUDE_VISION_CONTROL = 2,
69 ALTITUDE_VISION_CONTROL_TAKEOFF_TRIM = 3,
70 MULTICONFIGURATION = 1024
75 * @brief Possible states of the drone 'control' thread.
79 NO_CONTROL_MODE = 0, /*<! Doing nothing */
80 ARDRONE_UPDATE_CONTROL_MODE, /*<! Deprecated - Ardrone software update reception (update is done next run) */
81 /*<! After event completion, card should power off */
82 PIC_UPDATE_CONTROL_MODE, /*<! Ardrone PIC software update reception (update is done next run) */
83 /*<! After event completion, card should power off */
84 LOGS_GET_CONTROL_MODE, /*<! Send previous run's logs */
85 CFG_GET_CONTROL_MODE, /*<! Send active configuration file to a client through the 'control' socket UDP 5559 */
86 ACK_CONTROL_MODE, /*<! Reset command mask in navdata */
87 CUSTOM_CFG_GET_CONTROL_MODE /*<! Requests the list of custom configuration IDs */
88 } ARDRONE_CONTROL_MODE;
91 * @brief Drone video channels selection values.
92 * A client can choose to receive video data from the horizontal camera,
93 * the vertical one, or both (in a Picture-In-Picture way).
97 ZAP_CHANNEL_FIRST = 0, /*<! First element */
98 ZAP_CHANNEL_HORI = ZAP_CHANNEL_FIRST, /*<! Selects the horizontal camera */
99 ZAP_CHANNEL_VERT, /*<! Selects the vertical camera */
100 ZAP_CHANNEL_LARGE_HORI_SMALL_VERT, /*<! Selects the horizontal camera with vertical camera picture inserted in the left-top corner */
101 ZAP_CHANNEL_LARGE_VERT_SMALL_HORI, /*<! Selects the vertical camera with horizontal camera picture inserted in the left-top corner */
102 ZAP_CHANNEL_LAST = ZAP_CHANNEL_LARGE_VERT_SMALL_HORI, /*<! Last element */
103 ZAP_CHANNEL_NEXT, /*<! Selects the next available format among those above. */
107 * @brief Values for the detection type on drone cameras.
111 CAD_TYPE_HORIZONTAL = 0, /*<! Deprecated */
112 CAD_TYPE_VERTICAL, /*<! Deprecated */
113 CAD_TYPE_VISION, /*<! Detection of 2D horizontal tags on drone shells */
114 CAD_TYPE_NONE, /*<! Detection disabled */
115 CAD_TYPE_COCARDE, /*<! Detects a roundel under the drone */
116 CAD_TYPE_ORIENTED_COCARDE, /*<! Detects an oriented roundel under the drone */
117 CAD_TYPE_STRIPE, /*<! Detects a uniform stripe on the ground */
118 CAD_TYPE_H_COCARDE, /*<! Detects a roundel in front of the drone */
119 CAD_TYPE_H_ORIENTED_COCARDE, /*<! Detects an oriented roundel in front of the drone */
121 CAD_TYPE_MULTIPLE_DETECTION_MODE, /* The drone uses several detections at the same time */
122 CAD_TYPE_CAP, /*<! Detects a Cap orange and green in front of the drone */
123 CAD_TYPE_NUM, /*<! Number of possible values for CAD_TYPE */
126 /* Type of tag to detect
127 * This enum deprecates 'CAD_TYPE' which did not allow to mix tag types and cameras */
133 TAG_TYPE_ORIENTED_ROUNDEL ,
139 #define TAG_TYPE_MASK(tagtype) ( ((tagtype)==0)? 0 : (1<<((tagtype)-1)) )
143 DETECTION_SOURCE_CAMERA_HORIZONTAL=0, /*<! Tag was detected on the front camera picture */
144 DETECTION_SOURCE_CAMERA_VERTICAL, /*<! Tag was detected on the vertical camera picture at full speed */
145 DETECTION_SOURCE_CAMERA_VERTICAL_HSYNC, /*<! Tag was detected on the vertical camera picture inside the horizontal pipeline */
146 DETECTION_SOURCE_CAMERA_NUM,
147 }DETECTION_SOURCE_CAMERA;
149 #define DETECTION_MAKE_TYPE(source,tag) ( ((source)<<16) | (tag) )
150 #define DETECTION_EXTRACT_SOURCE(type) ( ((type)>>16) & 0x0FF )
151 #define DETECTION_EXTRACT_TAG(type) ( (type) & 0x0FF )
154 * @brief Video bitrate control mode.
158 VBC_MODE_DISABLED = 0, /*<! no video bitrate control */
159 VBC_MODE_DYNAMIC, /*<! video bitrate control active */
160 VBC_MANUAL /*<! video bitrate control active */
161 } VIDEO_BITRATE_CONTROL_MODE;
164 * @brief 2D-tag color values, used by the detection algorithms.
168 ARDRONE_DETECTION_COLOR_ORANGE_GREEN = 1, /*!< Cameras detect orange-green-orange tags */
169 ARDRONE_DETECTION_COLOR_ORANGE_YELLOW, /*!< Cameras detect orange-yellow-orange tags*/
170 ARDRONE_DETECTION_COLOR_ORANGE_BLUE, /*!< Cameras detect orange-blue-orange tags */
171 ARDRONE_DETECTION_COLOR_ARRACE_FINISH_LINE=0x10,
172 ARDRONE_DETECTION_COLOR_ARRACE_DONUT=0x11
173 } COLORS_DETECTION_TYPE, ENEMY_COLORS_TYPE;
176 * @brief User-control mode setting in FreeFlight.
177 * @description Bit mask showing how a user of the FreeFlight app. controls their drone.
181 // This is a bit to shift
182 // CONTROL_LEVEL_NOT_USED = 0,
183 CONTROL_LEVEL_COMBINED_YAW = 1, /*!< =1 : drone tilts sideward and turns simultaneously */
184 // CONTROL_LEVEL_NOT_USED = 2,
185 //4 used for CONTROL_LEVEL_CONTROL_MODE_BIT
189 * @enum LED_ANIMATION_IDS
190 * @brief Led animation values.
191 * See ardrone_at_set_led_animation function.
194 typedef enum LED_ANIMATION_IDS_
196 #define LED_ANIMATION(NAME, ... ) NAME ,
197 #include <led_animation.h>
202 typedef enum ARDRONE_PROGRESSIVE_CMD_FLAG_
204 ARDRONE_PROGRESSIVE_CMD_ENABLE, // 1: use progressive commands - 0: try hovering
205 ARDRONE_PROGRESSIVE_CMD_COMBINED_YAW_ACTIVE, // 1: activate combined yaw - 0: Deactivate combined yaw
206 ARDRONE_PROGRESSIVE_CMD_MAX
207 } ARDRONE_PROGRESSIVE_CMD_FLAG;
210 * @struct _euler_angles_t
211 * @brief Euler angles in float32_t format expressed in radians.
213 typedef struct _euler_angles_t
215 float32_t theta; /*<! Drone front-back angle (pitch) */
216 float32_t phi; /*<! Drone left-right angle (roll) */
217 float32_t psi; /*<! Drone orientation (yaw) */
221 * @struct _euler_angles_t
222 * @brief Euler angles in int32_t format expressed in radians.
224 typedef struct _iEuler_angles_t
226 int32_t theta; /*<! Drone front-back angle (pitch) */
227 int32_t phi; /*<! Drone left-right angle (roll) */
228 int32_t psi; /*<! Drone orientation (yaw) */
232 * @struct _angular_rates_t
233 * @brief Angular rates in float32_t format
235 typedef struct _angular_rates_t {
236 float32_t p; /*<! Drone front-back angular rate (pitch) */
237 float32_t q; /*<! Drone left-right angular rate (roll) */
238 float32_t r; /*<! Drone orientation angular rate (yaw) */
242 * \struct _velocities_t
243 * \brief Velocities in float32_t format
246 typedef struct _velocities_t {
254 * @struct _acq_vision_t
255 * @brief Deprecated - used internally by the drone - Vision params in float32_t
257 #ifndef DISABLE_DEPRECATED_CODE
258 typedef struct _acq_vision_t {
265 int32_t turn_finished;
272 * @struct _polaris_data_t
273 * @brief Used by Parrot only - drone externally-measured position in 3D-space
275 typedef struct _polaris_data_t
285 * @struct api_control_gains_t
286 * @brief Drone control loop PID settings
288 typedef struct _api_control_gains_t
290 int32_t pq_kp; /**< Gain for proportional correction in pitch (p) and roll (q) angular rate control */
291 int32_t r_kp; /**< Gain for proportional correction in yaw (r) angular rate control */
292 int32_t r_ki; /**< Gain for integral correction in yaw (r) angular rate control */
293 int32_t ea_kp; /**< Gain for proportional correction in Euler angle control */
294 int32_t ea_ki; /**< Gain for integral correction in Euler angle control */
295 int32_t alt_kp; /**< Gain for proportional correction in Altitude control */
296 int32_t alt_ki; /**< Gain for integral correction in Altitude control */
297 int32_t vz_kp; /**< Gain for proportional correction in Vz control */
298 int32_t vz_ki; /**< Gain for integral correction in Vz control */
299 int32_t hovering_kp; /**< Gain for proportional correction in hovering control */
300 int32_t hovering_ki; /**< Gain for integral correction in hovering control */
301 int32_t hovering_b_kp; /**< Gain for proportional correction in hovering beacon control */
302 int32_t hovering_b_ki; /**< Gain for integral correction in hovering beacon control */
303 } api_control_gains_t;
306 * @struct _api_vision_tracker_params_t
307 * @brief Computer vision tracking settings
309 typedef struct _api_vision_tracker_params_t
311 int32_t coarse_scale; /**< scale of current picture with respect to original picture */
312 int32_t nb_pair; /**< number of searched pairs in each direction */
313 int32_t loss_per; /**< authorized lost pairs percentage for tracking */
314 int32_t nb_tracker_width; /**< number of trackers in width of current picture */
315 int32_t nb_tracker_height; /**< number of trackers in height of current picture */
316 int32_t scale; /**< distance between two pixels in a pair */
317 int32_t trans_max; /**< largest value of trackers translation between two adjacent pictures */
318 int32_t max_pair_dist; /**< largest distance of pairs research from tracker location */
319 int32_t noise; /**< threshold of meaningful contrast */
320 } api_vision_tracker_params_t;
324 * @brief Values for the CONTROL:flying_mode configuration.
328 FLYING_MODE_FREE_FLIGHT=0, /**< Normal mode, commands are enabled */
329 FLYING_MODE_HOVER_ON_TOP_OF_ROUNDEL, /**< Commands are disabled, drones hovers on top of a roundel - roundel detection MUST be activated by the user with 'detect_type' configuration. */
335 * @brief Values for the NETWORK:wifi_mode configuration, who set the wifi mode when drone start
339 WIFI_MODE_INFRA = 0, /**< Access point mode */
340 WIFI_MODE_ADHOC , /**< Ad-Hoc mode */
341 WIFI_MODE_MANAGED, /**< Managed mode */
345 /********************************************************************
347 ********************************************************************/
350 * @struct _navdata_unpacked_t
351 * @brief Decoded navigation data.
353 typedef struct _navdata_unpacked_t
355 uint32_t ardrone_state;
356 bool_t vision_defined;
357 uint32_t last_navdata_refresh; /*! mask showing which block was refreshed when receiving navdata */
359 #define NAVDATA_OPTION_DEMO(STRUCTURE,NAME,TAG) STRUCTURE NAME ;
360 #define NAVDATA_OPTION(STRUCTURE,NAME,TAG) STRUCTURE NAME ;
361 #define NAVDATA_OPTION_CKS(STRUCTURE,NAME,TAG)
362 #include <navdata_keys.h>
364 } navdata_unpacked_t;
367 * @def ardrone_navdata_pack
368 * @brief Add an 'option' to the navdata network packet to be sent to a client.
369 * Used by the drone 'navdata' thread.
371 #define ardrone_navdata_pack( navdata_ptr, option ) (navdata_option_t*) navdata_pack_option( (uint8_t*) navdata_ptr, \
372 (uint8_t*) &option, \
376 * @def ardrone_navdata_unpack
377 * @brief Extract an'option' from the navdata network packet sent by the drone.
378 * Used by the client 'navdata' thread inside ARDroneTool.
380 #define ardrone_navdata_unpack( navdata_ptr, option ) (navdata_option_t*) navdata_unpack_option( (uint8_t*) navdata_ptr, \
382 (uint8_t*) &option, \
386 * @brief Add an 'option' to the navdata network packet to be sent to a client.
387 * Used by the drone 'navdata' thread.
388 * @param navdata_ptr Pointer to the buffer containing packed navdata to be sent.
390 static INLINE uint8_t* navdata_pack_option( uint8_t* navdata_ptr, uint8_t* data, uint32_t size )
392 vp_os_memcpy(navdata_ptr, data, size);
393 return (navdata_ptr + size);
397 * @fn navdata_unpack_option
398 * @brief Extract an 'option' from the navdata network packet sent by the drone.
399 * Used by the client 'navdata' thread inside ARDroneTool.
401 static INLINE uint8_t* navdata_unpack_option( uint8_t* navdata_ptr, uint32_t ptrsize, uint8_t* data, uint32_t datasize )
403 uint32_t minSize = (ptrsize < datasize) ? ptrsize : datasize;
404 vp_os_memcpy(data, navdata_ptr, minSize);
405 return (navdata_ptr + ptrsize);
409 * @fn navdata_next_option
410 * @brief Jumps to the next 'option' inside the packed navdata.
411 * Used by the client 'navdata' thread inside ARDroneTool.
413 static INLINE navdata_option_t* navdata_next_option( navdata_option_t* navdata_options_ptr )
417 ptr = (uint8_t*) navdata_options_ptr;
418 ptr += navdata_options_ptr->size;
420 return (navdata_option_t*) ptr;
424 * @brief Creates a checksum from a packed navdata packet.
425 * @param nv Data to calculate the checksum.
426 * @param size Size of data calculate as follow : size-sizeof(navdata_cks_t).
427 * @return Retrieves the checksum from the navdata nv.
429 uint32_t ardrone_navdata_compute_cks( uint8_t* nv, int32_t size ) API_WEAK;
432 * @param navdata_unpacked navdata_unpacked in which to store the navdata.
433 * @param navdata One packet read from the port NAVDATA.
434 * @param Checksum of navdata
435 * @brief Disassembles a buffer of received navdata, and dispatches it inside 'navdata_unpacked' structure.
437 C_RESULT ardrone_navdata_unpack_all(navdata_unpacked_t* navdata_unpacked, navdata_t* navdata, uint32_t* cks) API_WEAK;
440 * @param navdata_options_ptr
441 * @param Tag ID of the bloc to search for.
442 * @brief Jumps to a specified 'option' (block of navdata) inside a navdata packed buffer.
444 navdata_option_t* ardrone_navdata_search_option( navdata_option_t* navdata_options_ptr, navdata_tag_t tag ) API_WEAK;
446 /********************************************************************
448 ********************************************************************/
451 * @brief Initializes the AT Command managing thread of ARDroneTool.
452 * The AT Codec is initialized.
454 void ardrone_at_init( const char* ip, size_t ip_len ) API_WEAK;
457 * @brief Initializes the AT Command managing thread of ARDroneTool, by
458 * providing it with custom functions for I/O from/to the drone.
460 void ardrone_at_init_with_funcs ( const char* ip, size_t ip_len, AT_CODEC_FUNCTIONS_PTRS *funcs) API_WEAK;
463 * @fn ardrone_at_open
464 * @brief Opens the AT command socket.
466 ATCODEC_RET ardrone_at_open ( void ) API_WEAK;
469 * @brief Makes ARDroneToll send all queued AT commands to the drone.
470 * ARDroneTool locally buffers AT commands sent by the client program
471 * until this function is called.
472 * Usually the client program GUI calls ardrone_at_xxx commands to
473 * pilot the drone; these commands are then queued by ARDroneTool.
474 * The ARDroneTool main thread calls this functions periodically
475 * (every 30ms for example) to actually send to queued commands to
478 ATCODEC_RET ardrone_at_send ( void ) API_WEAK;
481 * @brief Sends input sequence number to avoid reception of old data
482 * @param value : sequence number
485 * Used on prototypes.
487 //void ardrone_at_set_sequence( uint32_t sequence ) API_WEAK;
490 * @brief Set the flight status command.
491 * @param value Bit mask containing the desired commmand.
492 * The bit mask contains the bit controlling take-off/landing
493 * and the bit signaling /resuming from an emergency.
494 * This mask is periodically sent to the drone by ARDroneTool
495 * inside an AT*REF command.
497 void ardrone_at_set_ui_value( uint32_t value ) API_WEAK;
500 * @brief Used internally by Parrot - send misc. config. data.
501 * @param data used to configure control
504 void ardrone_at_set_pmode( int32_t pmode ) API_WEAK;
506 #ifndef DISABLE_DEPRECATED_CODE
508 * @fn Tell to keep trim result
512 void ardrone_at_keep_trim( bool_t keep ) API_WEAK;
515 * @fn Reset trim/misc0 related ack's
518 void ardrone_at_trim_ack_reset( void ) API_WEAK;
522 * @brief Used by Parrot - send misc. config. data for drone debugging.
523 * @param data are used to configure control (for instance)
525 * This should not be used by SDK users. Parameters value do not have any fixed meaning.
527 void ardrone_at_set_ui_misc( int32_t m1, int32_t m2, int32_t m3, int32_t m4 ) API_WEAK;
530 * @brief Makes the drone play a predefined movement
531 * @param type type of animation
532 * @param timeout duration of the animation in seconds
534 void ardrone_at_set_anim( anim_mayday_t type, int32_t timeout ) API_WEAK;
537 * @brief Instructs the drone to use its current position
538 * as a reference for the horizontal plane.
540 void ardrone_at_set_flat_trim( void ) API_WEAK;
543 * @brief Sets a manual trim (offset) on the drone commands
545 void ardrone_at_set_manual_trims( float32_t trim_pitch, float32_t trim_roll, float32_t trim_yaw ) API_WEAK;
548 * @brief Changes PID gains of the drone control loop
549 * @param user_ctrl_gains gains to be set
551 void ardrone_at_set_control_gains( api_control_gains_t* user_ctrl_gains ) API_WEAK;
554 * @brief Changes the tracking parameters (only in UE_IHM_PO mode)
555 * @param params : new params
557 void ardrone_at_set_vision_track_params( api_vision_tracker_params_t* params ) API_WEAK;
560 * @fn Start a raw capture
562 void ardrone_at_start_raw_capture(void) API_WEAK;
565 * @brief Changes the type of object to detect
567 void ardrone_at_cad( CAD_TYPE type, float32_t tag_size ) API_WEAK;
570 * @brief Change the broadcasted video channel
572 void ardrone_at_zap( ZAP_VIDEO_CHANNEL channel ) API_WEAK;
575 * @brief Plays a led animation
577 void ardrone_at_set_led_animation ( LED_ANIMATION_IDS anim_id, float32_t freq, uint32_t duration_sec ) API_WEAK;
580 * @fn Set vision update options (only in UE_IHM_PO mode)
581 * @param user_vision_option : new option
583 void ardrone_at_set_vision_update_options( int32_t user_vision_option ) API_WEAK;
586 * @brief Used internally at Parrot - sets the drones position as seen by polaris
587 * @param x_polaris : x of ardrone position seen by polaris
588 * @param y_polaris : y of ardrone position seen by polaris
589 * @param defined : tells if polaris data are valid or not
590 * @param time_us : time in us
592 void ardrone_at_set_polaris_pos( float32_t x_polaris, float32_t y_polaris, float32_t psi_polaris, bool_t defined, int32_t time_us ) API_WEAK;
595 * @brief Used internally at Parrot - sets the drones position as seen by vicon
596 * @param time : vicon timestamp
597 * @param frame_number : vicon frame_number
598 * @param latency : vicon latency
599 * @param global_translation : vicon global translation
600 * @param global_rotation_euler : vicon global rotation (euler angles)
602 void ardrone_at_set_vicon_data(struct timeval time, int32_t frame_number, float32_t latency, vector31_t global_translation, vector31_t global_rotation_euler);
605 * @brief Send to drone a identified configuration
606 * @param param : parameter to set or update
607 * @param ses_id : session id
608 * @param usr_id : user id
609 * @param app_id : application id
610 * @param value : value to apply to the parameter
612 void ardrone_at_set_toy_configuration_ids(const char* param,char* ses_id, char* usr_id, char* app_id, const char* value) API_WEAK;
615 * @brief Asks the drone to reset the communication watchdog.
616 * If no command is received by the drone
618 void ardrone_at_reset_com_watchdog( void ) API_WEAK;
621 * @brief Asks the drone to purge log files
623 void ardrone_at_reset_logs( void ) API_WEAK;
626 * @brief Asks the drone we receive a plf with a size filesize
628 void ardrone_at_update_control_mode( uint32_t what_to_do, uint32_t filesize ) API_WEAK;
631 * @brief Asks the drone to send control mode
633 void ardrone_at_configuration_get_ctrl_mode( void ) API_WEAK;
634 void ardrone_at_custom_configuration_get_ctrl_mode(void) API_WEAK;
637 * @brief Tells the drone we received the control mode
639 void ardrone_at_configuration_ack_ctrl_mode( void ) API_WEAK;
641 void ardrone_at_set_autonomous_flight( int32_t isActive );
644 * @brief Sets the drone motor command directly
645 * This is enables only on prototypes drones.
647 void ardrone_at_set_pwm( int32_t p1, int32_t p2, int32_t p3, int32_t p4 ) API_WEAK;
650 * @fn ardrone_at_set_progress_cmd
651 * @brief Sends the drone progressive commands
652 * @param flag Use 1 << value of ARDRONE_PROGRESSIVE_CMD_FLAG_XXX to use a flag
653 * @param phi Left/right angle between -1 to +1 - negative values bend leftward.
654 * @param roll Front/back angle between -1 to +1 - negative values bend forward.
655 * @param gaz Vertical speed - negative values make the drone go down.
656 * @param yaw Angular speed - negative values make the drone spin left.
657 * This function allows the client program to control the drone by giving it a front/back
658 * and left/right bending order, a vertical speed order, and a rotation order.
659 * All values are given as a percentage of the maximum bending angles (in degrees),
660 * vertical speed (in millimeters per second) and angular speed (in degrees per second).
662 void ardrone_at_set_progress_cmd( int32_t flag, float32_t phi, float32_t theta, float32_t gaz, float32_t yaw );
665 /*****************************************************************
666 * AT CONFIG FUNCTIONS
667 *****************************************************************/
668 #undef ARDRONE_CONFIG_KEY_IMM
669 #undef ARDRONE_CONFIG_KEY_REF
670 #undef ARDRONE_CONFIG_KEY_STR
671 #define ARDRONE_CONFIG_KEY_IMM(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
672 #define ARDRONE_CONFIG_KEY_REF(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
673 #define ARDRONE_CONFIG_KEY_STR(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
674 #include <config_keys.h> // must be included before to have types
676 #undef ARDRONE_CONFIG_KEY_IMM
677 #undef ARDRONE_CONFIG_KEY_REF
678 #undef ARDRONE_CONFIG_KEY_STR
679 #define ARDRONE_CONFIG_KEY_IMM(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) ARDRONE_CONFIGURATION_PROTOTYPE(NAME);
680 #define ARDRONE_CONFIG_KEY_REF(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
681 #define ARDRONE_CONFIG_KEY_STR(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) ARDRONE_CONFIGURATION_PROTOTYPE(NAME);
682 #include <config_keys.h> // must be included before to have types
684 /********************************************************************
686 ********************************************************************/
687 #undef ARDRONE_CONFIG_KEY_IMM
688 #undef ARDRONE_CONFIG_KEY_REF
689 #undef ARDRONE_CONFIG_KEY_STR
690 #define ARDRONE_CONFIG_KEY_IMM(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
691 #define ARDRONE_CONFIG_KEY_REF(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
692 #define ARDRONE_CONFIG_KEY_STR(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
693 #include <config_keys.h> // must be included before to have types
695 #undef ARDRONE_CONFIG_KEY_IMM
696 #undef ARDRONE_CONFIG_KEY_REF
697 #undef ARDRONE_CONFIG_KEY_STR
698 #define ARDRONE_CONFIG_KEY_IMM(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) \
699 C_TYPE get_##NAME(void) API_WEAK; \
700 C_RESULT set_##NAME(C_TYPE val) API_WEAK;
701 #define ARDRONE_CONFIG_KEY_REF(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) \
702 C_TYPE_PTR get_##NAME(void) API_WEAK; \
703 C_RESULT set_##NAME(C_TYPE_PTR val) API_WEAK;
704 #define ARDRONE_CONFIG_KEY_STR(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) \
705 C_TYPE_PTR get_##NAME(void) API_WEAK; \
706 C_RESULT set_##NAME(C_TYPE_PTR val) API_WEAK;
707 // Generate all accessors functions prototypes
708 #include <config_keys.h>
711 #undef ARDRONE_CONFIG_KEY_IMM
712 #undef ARDRONE_CONFIG_KEY_REF
713 #undef ARDRONE_CONFIG_KEY_STR
714 #define ARDRONE_CONFIG_KEY_IMM(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
715 #define ARDRONE_CONFIG_KEY_REF(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
716 #define ARDRONE_CONFIG_KEY_STR(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK)
717 #include <config_keys.h> // must be included before to have types
719 #undef ARDRONE_CONFIG_KEY_IMM
720 #undef ARDRONE_CONFIG_KEY_REF
721 #undef ARDRONE_CONFIG_KEY_STR
722 #define ARDRONE_CONFIG_KEY_IMM(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) C_TYPE NAME;
723 #define ARDRONE_CONFIG_KEY_REF(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) C_TYPE NAME;
724 #define ARDRONE_CONFIG_KEY_STR(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, DEFAULT, CALLBACK) C_TYPE NAME;
726 // Fill structure fields types
727 typedef struct _ardrone_config_t
729 #include <config_keys.h>
733 void reset_ardrone_config(void);
735 /********************************************************************
737 ********************************************************************/
738 #define MULTICONFIG_ID_SIZE 9
739 #define SESSION_NAME_SIZE 1024
740 #define USER_NAME_SIZE 1024
741 #define APPLI_NAME_SIZE 1024
743 typedef struct _ardrone_user_t
745 char ident[MULTICONFIG_ID_SIZE];
746 char description[USER_NAME_SIZE];
749 typedef struct _ardrone_users_t
752 ardrone_user_t *userList;
755 void ardrone_refresh_user_list(void); // Ask for a userlist refresh
756 void ardrone_switch_to_user(const char *new_user); // Can be used to create user
757 void ardrone_switch_to_user_id(const char *new_user_id); // Must be used only with existing users
758 ardrone_users_t *ardrone_get_user_list(void); // Get a list of users (MUST BE FREED BY A ardrone_free_user_list CALL)
759 void ardrone_free_user_list (ardrone_users_t **users); // Free an ardrone_users_t list allocated by ardrone_get_user_list
762 #endif // _ARDRONE_API_H_