Defines | Functions | Variables
waypoints.c File Reference
#include "waypoints.h"
#include <math.h>
Include dependency graph for waypoints.c:

Go to the source code of this file.

Defines

#define MAVLINK_WPM_NO_PRINTF

Functions

void mavlink_missionlib_current_waypoint_changed (uint16_t index, float param1, float param2, float param3, float param4, float param5_lat_x, float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command)
uint64_t mavlink_missionlib_get_system_timestamp ()
void mavlink_missionlib_send_gcs_string (const char *string)
void mavlink_missionlib_send_message (mavlink_message_t *msg)
float mavlink_wpm_distance_to_point (uint16_t seq, float x, float y, float z)
void mavlink_wpm_init (mavlink_wpm_storage *state)
void mavlink_wpm_loop ()
void mavlink_wpm_message_handler (const mavlink_message_t *msg)
void mavlink_wpm_send_setpoint (uint16_t seq)
void mavlink_wpm_send_waypoint (uint8_t sysid, uint8_t compid, uint16_t seq)
void mavlink_wpm_send_waypoint_ack (uint8_t sysid, uint8_t compid, uint8_t type)
void mavlink_wpm_send_waypoint_count (uint8_t sysid, uint8_t compid, uint16_t count)
void mavlink_wpm_send_waypoint_current (uint16_t seq)
void mavlink_wpm_send_waypoint_reached (uint16_t seq)
void mavlink_wpm_send_waypoint_request (uint8_t sysid, uint8_t compid, uint16_t seq)

Variables

bool debug = true
uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER
bool verbose = true
mavlink_wpm_storage wpm

Define Documentation

Definition at line 36 of file waypoints.c.


Function Documentation

void mavlink_missionlib_current_waypoint_changed ( uint16_t  index,
float  param1,
float  param2,
float  param3,
float  param4,
float  param5_lat_x,
float  param6_lon_y,
float  param7_alt_z,
uint8_t  frame,
uint16_t  command 
)

Definition at line 163 of file main.c.

void mavlink_missionlib_send_gcs_string ( const char *  string)

Definition at line 144 of file main.c.

Definition at line 135 of file main.c.

float mavlink_wpm_distance_to_point ( uint16_t  seq,
float  x,
float  y,
float  z 
)

Definition at line 270 of file waypoints.c.

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

void mavlink_wpm_send_setpoint ( uint16_t  seq)

Definition at line 132 of file waypoints.c.

void mavlink_wpm_send_waypoint ( uint8_t  sysid,
uint8_t  compid,
uint16_t  seq 
)

Definition at line 166 of file waypoints.c.

void mavlink_wpm_send_waypoint_ack ( uint8_t  sysid,
uint8_t  compid,
uint8_t  type 
)

Definition at line 66 of file waypoints.c.

void mavlink_wpm_send_waypoint_count ( uint8_t  sysid,
uint8_t  compid,
uint16_t  count 
)

Definition at line 149 of file waypoints.c.

void mavlink_wpm_send_waypoint_current ( uint16_t  seq)

Definition at line 100 of file waypoints.c.

void mavlink_wpm_send_waypoint_reached ( uint16_t  seq)

Definition at line 214 of file waypoints.c.

void mavlink_wpm_send_waypoint_request ( uint8_t  sysid,
uint8_t  compid,
uint16_t  seq 
)

Definition at line 186 of file waypoints.c.


Variable Documentation

bool debug = true

Definition at line 23 of file waypoints.c.

uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER

Definition at line 38 of file waypoints.c.

bool verbose = true

Definition at line 24 of file waypoints.c.

Definition at line 80 of file main.c.



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