Classes | Defines | Typedefs | Enumerations | Functions | Variables
waypoints.h File Reference
#include <mavlink_types.h>
#include <mavlink.h>
#include <stdbool.h>
Include dependency graph for waypoints.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  mavlink_wpm_storage

Defines

#define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE
 Enable double buffer and in-flight updates.
#define MAVLINK_WPM_MAX_WP_COUNT   15
#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT   40
#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT   5000
 Protocol communication timeout in milliseconds.
#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT   1000
 When to send a new setpoint.

Typedefs

typedef struct mavlink_wpm_storage mavlink_wpm_storage

Enumerations

enum  MAVLINK_WPM_CODES {
  MAVLINK_WPM_CODE_OK = 0, MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED, MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED, MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS,
  MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED, MAVLINK_WPM_CODE_ENUM_END
}
enum  MAVLINK_WPM_STATES {
  MAVLINK_WPM_STATE_IDLE = 0, MAVLINK_WPM_STATE_SENDLIST, MAVLINK_WPM_STATE_SENDLIST_SENDWPS, MAVLINK_WPM_STATE_GETLIST,
  MAVLINK_WPM_STATE_GETLIST_GETWPS, MAVLINK_WPM_STATE_GETLIST_GOTALL, MAVLINK_WPM_STATE_ENUM_END
}

Functions

void mavlink_send_uart_bytes (mavlink_channel_t chan, uint8_t *buffer, uint16_t len)
void mavlink_wpm_init (mavlink_wpm_storage *state)
void mavlink_wpm_loop ()
void mavlink_wpm_message_handler (const mavlink_message_t *msg)

Variables

mavlink_system_t mavlink_system

Define Documentation

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.

Definition at line 70 of file waypoints.h.

Protocol communication timeout in milliseconds.

Definition at line 68 of file waypoints.h.

When to send a new setpoint.

Definition at line 69 of file waypoints.h.


Typedef Documentation

Definition at line 100 of file waypoints.h.


Enumeration Type Documentation

Enumerator:
MAVLINK_WPM_CODE_OK 
MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED 
MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED 
MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS 
MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED 
MAVLINK_WPM_CODE_ENUM_END 

Definition at line 50 of file waypoints.h.

Enumerator:
MAVLINK_WPM_STATE_IDLE 
MAVLINK_WPM_STATE_SENDLIST 
MAVLINK_WPM_STATE_SENDLIST_SENDWPS 
MAVLINK_WPM_STATE_GETLIST 
MAVLINK_WPM_STATE_GETLIST_GETWPS 
MAVLINK_WPM_STATE_GETLIST_GOTALL 
MAVLINK_WPM_STATE_ENUM_END 

Definition at line 39 of file waypoints.h.


Function Documentation

void mavlink_send_uart_bytes ( mavlink_channel_t  chan,
uint8_t *  buffer,
uint16_t  len 
)

< 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.

Definition at line 317 of file waypoints.c.


Variable Documentation

Definition at line 65 of file main.c.



mavlink
Author(s): Lorenz Meier
autogenerated on Sun May 22 2016 04:05:43