Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
messages parser for mission interface More...
#include "modules/mission/mission_common.h"
#include <string.h>
#include "generated/flight_plan.h"
#include "generated/airframe.h"
#include "modules/datalink/datalink.h"
#include "modules/datalink/downlink.h"
#include "modules/datalink/telemetry.h"
Go to the source code of this file.
Macros | |
#define | MISSION_CHECK_UNIQUE_ID TRUE |
Functions | |
static void | send_mission_status (struct transport_tx *trans, struct link_device *device) |
void | mission_init (void) |
Init mission structure. More... | |
bool | mission_insert (enum MissionInsertMode insert, struct _mission_element *element) |
Insert a mission element according to the insertion mode. More... | |
bool | mission_register (mission_custom_cb cb, char *type) |
Register a new navigation or action callback function. More... | |
static struct _mission_registered * | mission_get_registered (char *type) |
struct _mission_element * | mission_get_from_index (uint8_t index) |
Get mission element by index. More... | |
struct _mission_element * | mission_get (void) |
Get current mission element. More... | |
void | mission_status_report (void) |
Report mission status. More... | |
int | mission_parse_GOTO_WP (uint8_t *buf) |
Parsing functions called when a mission message is received. More... | |
int | mission_parse_GOTO_WP_LLA (uint8_t *buf) |
int | mission_parse_CIRCLE (uint8_t *buf) |
int | mission_parse_CIRCLE_LLA (uint8_t *buf) |
int | mission_parse_SEGMENT (uint8_t *buf) |
int | mission_parse_SEGMENT_LLA (uint8_t *buf) |
int | mission_parse_PATH (uint8_t *buf) |
int | mission_parse_PATH_LLA (uint8_t *buf) |
int | mission_parse_CUSTOM (uint8_t *buf) |
int | mission_parse_UPDATE (uint8_t *buf) |
int | mission_parse_GOTO_MISSION (uint8_t *buf) |
int | mission_parse_NEXT_MISSION (uint8_t *buf) |
int | mission_parse_END_MISSION (uint8_t *buf) |
Variables | |
struct _mission | mission = { 0 } |
messages parser for mission interface
Definition in file mission_common.c.
#define MISSION_CHECK_UNIQUE_ID TRUE |
Definition at line 40 of file mission_common.c.
struct _mission_element* mission_get | ( | void | ) |
Get current mission element.
Definition at line 178 of file mission_common.c.
References _mission::current_idx, _mission::elements, _mission::insert_idx, and mission.
Referenced by mission_run().
struct _mission_element* mission_get_from_index | ( | uint8_t | index | ) |
Get mission element by index.
Definition at line 162 of file mission_common.c.
References _mission::current_idx, _mission::elements, _mission_element::index, _mission::insert_idx, mission, and MISSION_ELEMENT_NB.
Referenced by mission_insert(), and mission_parse_UPDATE().
|
static |
Definition at line 151 of file mission_common.c.
References mission, MISSION_REGISTER_NB, _mission::registered, and _mission_registered::type.
Referenced by mission_parse_CUSTOM().
void mission_init | ( | void | ) |
Init mission structure.
Definition at line 65 of file mission_common.c.
References _mission_registered::cb, _mission::current_idx, DefaultPeriodic, _mission::element_time, _mission::insert_idx, mission, MISSION_REGISTER_NB, MISSION_TYPE_SIZE, register_periodic_telemetry(), _mission::registered, send_mission_status(), and _mission_registered::type.
bool mission_insert | ( | enum MissionInsertMode | insert, |
struct _mission_element * | element | ||
) |
Insert a mission element according to the insertion mode.
insert | insertion mode |
element | mission element structure |
Definition at line 83 of file mission_common.c.
References Append, _mission::current_idx, _mission::element_time, _mission::elements, _mission_element::index, _mission::insert_idx, mission, MISSION_ELEMENT_NB, mission_get_from_index(), Prepend, ReplaceAll, ReplaceCurrent, and ReplaceNexts.
Referenced by mission_parse_CIRCLE(), mission_parse_CIRCLE_LLA(), mission_parse_CUSTOM(), mission_parse_GOTO_WP(), mission_parse_GOTO_WP_LLA(), mission_parse_PATH(), mission_parse_PATH_LLA(), mission_parse_SEGMENT(), and mission_parse_SEGMENT_LLA().
int mission_parse_CIRCLE | ( | uint8_t * | buf | ) |
Definition at line 236 of file mission_common.c.
References _mission_element::duration, _mission_element::element, _mission_element::index, mission_insert(), MissionCircle, and _mission_element::type.
int mission_parse_CIRCLE_LLA | ( | uint8_t * | buf | ) |
Definition at line 254 of file mission_common.c.
References LlaCoor_i::alt, _mission_element::duration, _mission_element::element, _mission_element::index, LlaCoor_i::lat, LlaCoor_i::lon, mission_insert(), mission_point_of_lla(), MissionCircle, and _mission_element::type.
int mission_parse_CUSTOM | ( | uint8_t * | buf | ) |
Definition at line 392 of file mission_common.c.
References _mission_element::duration, _mission_element::element, _mission_element::index, mission_get_registered(), mission_insert(), MissionCustom, and _mission_element::type.
int mission_parse_END_MISSION | ( | uint8_t * | buf | ) |
Definition at line 474 of file mission_common.c.
References _mission::current_idx, _mission::element_time, _mission::insert_idx, and mission.
int mission_parse_GOTO_MISSION | ( | uint8_t * | buf | ) |
Definition at line 446 of file mission_common.c.
References _mission::current_idx, _mission::element_time, mission, and MISSION_ELEMENT_NB.
int mission_parse_GOTO_WP | ( | uint8_t * | buf | ) |
Parsing functions called when a mission message is received.
Definition at line 198 of file mission_common.c.
References _mission_element::duration, _mission_element::element, _mission_element::index, mission_insert(), MissionWP, and _mission_element::type.
int mission_parse_GOTO_WP_LLA | ( | uint8_t * | buf | ) |
Definition at line 215 of file mission_common.c.
References LlaCoor_i::alt, _mission_element::duration, _mission_element::element, _mission_element::index, LlaCoor_i::lat, LlaCoor_i::lon, mission_insert(), mission_point_of_lla(), MissionWP, and _mission_element::type.
int mission_parse_NEXT_MISSION | ( | uint8_t * | buf | ) |
Definition at line 461 of file mission_common.c.
References _mission::current_idx, _mission::element_time, _mission::insert_idx, mission, and MISSION_ELEMENT_NB.
int mission_parse_PATH | ( | uint8_t * | buf | ) |
Definition at line 321 of file mission_common.c.
References _mission_element::duration, _mission_element::element, _mission_element::index, mission_insert(), MISSION_PATH_NB, MissionPath, and _mission_element::type.
int mission_parse_PATH_LLA | ( | uint8_t * | buf | ) |
Definition at line 353 of file mission_common.c.
References LlaCoor_i::alt, _mission_element::duration, _mission_element::element, _mission_element::index, LlaCoor_i::lat, LlaCoor_i::lon, mission_insert(), MISSION_PATH_NB, mission_point_of_lla(), MissionPath, and _mission_element::type.
int mission_parse_SEGMENT | ( | uint8_t * | buf | ) |
Definition at line 276 of file mission_common.c.
References _mission_element::duration, _mission_element::element, _mission_element::index, mission_insert(), MissionSegment, and _mission_element::type.
int mission_parse_SEGMENT_LLA | ( | uint8_t * | buf | ) |
Definition at line 296 of file mission_common.c.
References LlaCoor_i::alt, _mission_element::duration, _mission_element::element, _mission_element::index, LlaCoor_i::lat, LlaCoor_i::lon, mission_insert(), mission_point_of_lla(), MissionSegment, and _mission_element::type.
int mission_parse_UPDATE | ( | uint8_t * | buf | ) |
Definition at line 414 of file mission_common.c.
References _mission_element::duration, _mission_element::element, MISSION_CUSTOM_MAX, mission_get_from_index(), MissionCircle, MissionCustom, MissionPath, MissionSegment, MissionUpdate, MissionWP, and _mission_element::type.
bool mission_register | ( | mission_custom_cb | cb, |
char * | type | ||
) |
Register a new navigation or action callback function.
cb | callback f(nb, param array) |
type | string identifier with 5 characters max (+ 1 '\0' char) |
Definition at line 135 of file mission_common.c.
References _mission_registered::cb, mission, MISSION_REGISTER_NB, MISSION_TYPE_SIZE, _mission::registered, and _mission_registered::type.
Referenced by nav_lace_init(), nav_line_init(), nav_rosette_init(), nav_spiral_3D_init(), nav_survey_hybrid_init(), nav_takeoff_and_landing_init(), and nav_trinity_init().
void mission_status_report | ( | void | ) |
Report mission status.
Send mission status over datalink
Definition at line 188 of file mission_common.c.
References DefaultChannel, DefaultDevice, and send_mission_status().
|
static |
Definition at line 45 of file mission_common.c.
References _mission::current_idx, _mission_element::duration, _mission::element_time, _mission::elements, _mission_element::index, _mission::insert_idx, mission, and MISSION_ELEMENT_NB.
Referenced by mission_init(), and mission_status_report().
struct _mission mission = { 0 } |
Definition at line 1 of file mission_common.c.
Referenced by mission_get(), mission_get_from_index(), mission_get_registered(), mission_init(), mission_insert(), mission_nav_circle(), mission_parse_END_MISSION(), mission_parse_GOTO_MISSION(), mission_parse_NEXT_MISSION(), mission_register(), mission_run(), and send_mission_status().