#include <mavlink_types.h>#include <mavlink.h>#include <stdbool.h>

Go to the source code of this file.
Enable double buffer and in-flight updates.
Definition at line 64 of file waypoints.h.
| #define MAVLINK_WPM_MAX_WP_COUNT 15 | 
Definition at line 63 of file waypoints.h.
| #define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40 | 
Definition at line 70 of file waypoints.h.
| #define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000 | 
Protocol communication timeout in milliseconds.
Definition at line 68 of file waypoints.h.
| #define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000 | 
When to send a new setpoint.
Definition at line 69 of file waypoints.h.
| typedef struct mavlink_wpm_storage mavlink_wpm_storage | 
Definition at line 100 of file waypoints.h.
| enum MAVLINK_WPM_CODES | 
Definition at line 50 of file waypoints.h.
| enum MAVLINK_WPM_STATES | 
Definition at line 39 of file waypoints.h.
| void mavlink_send_uart_bytes | ( | mavlink_channel_t | chan, | 
| uint8_t * | buffer, | ||
| uint16_t | len | ||
| ) | 
| void mavlink_wpm_init | ( | mavlink_wpm_storage * | state | ) | 
< indicates if the system is following the waypoints or is waiting
< id of current waypoint
< boolean for yaw attitude reached
< boolean for position reached
< timestamp when the MAV was last outside the orbit or had the wrong yaw value
< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
Definition at line 40 of file waypoints.c.
| void mavlink_wpm_loop | ( | ) | 
Definition at line 288 of file waypoints.c.
| void mavlink_wpm_message_handler | ( | const mavlink_message_t * | msg | ) | 
Definition at line 317 of file waypoints.c.