|
ICAROUS
|
function declarations, definitions of macros, datastructures and global variables for the arudpilot application More...
#include "cfe.h"#include "cfe_error.h"#include "cfe_evs.h"#include "cfe_sb.h"#include "cfe_es.h"#include "cfe_platform_cfg.h"#include <string.h>#include <errno.h>#include <unistd.h>#include <network_includes.h>#include <arducopter_table.h>#include <arducopter_events.h>#include <arducopter_version.h>#include <Icarous.h>#include <traffic_msg.h>#include <traffic_msgids.h>#include <guidance_msg.h>#include <guidance_msgids.h>#include <Guidance.h>#include <geofence_msg.h>#include <geofence_msgids.h>#include <trajectory_msg.h>#include <trajectory_msgids.h>#include <sch_msgids.h>#include <mavlink/ardupilotmega/mavlink.h>#include <port_lib.h>Go to the source code of this file.
Classes | |
| struct | appdataInt_t |
| Structure to hold app data. More... | |
Macros | |
| #define | ARDUCOPTER_PIPE_NAME "FLIGHTPLAN" |
| #define | ARDUCOPTER_PIPE_DEPTH 100 |
| #define | SCH_ARDUCOPTER_PIPE1_NAME "SCH_ARDUCOPTER" |
Enumerations | |
| enum | controlMode_e { STABILIZE = 0 , ACRO = 1 , ALT_HOLD = 2 , AUTO = 3 , GUIDED = 4 , LOITER = 5 , RTL = 6 , CIRCLE = 7 , DRIFT = 11 , SPORT = 13 , FLIP = 14 , AUTOTUNE = 15 , POSHOLD = 16 , BRAKE = 17 , THROW = 18 , AVOID_ADSB = 19 , GUIDED_NOGPS = 20 } |
| enumeration for Arducopter control modes More... | |
Functions | |
| void | ARDUCOPTER_AppMain (void) |
| void | ARDUCOPTER_AppInit (void) |
| void | ARDUCOPTER_AppInitializeData (void) |
| void | ARDUCOPTER_AppCleanUp (void) |
| void | Task1 (void) |
| int | GetMAVLinkMsgFromAP (void) |
| void | ProcessAPMessage (mavlink_message_t message) |
| void | ARDUCOPTER_ProcessPacket (void) |
| void | apSendHeartbeat (void) |
| void | apSendCallsign (void) |
| void | ap_gfCallback (uint32_t timer) |
| void | ap_pmCallback (uint32_t timerId) |
| void | ap_tjCallback (uint32_t timerId) |
| void | ap_startTimer (uint32_t *timerID, void(*f)(uint32_t), char *name, uint32_t startTime, uint32_t intvl) |
| void | ap_stopTimer (uint32_t *timerID) |
| void | apInterface_PublishParams (void) |
| int32_t | ArducopterTableValidationFunc (void *TblPtr) |
| uint16_t | apConvertPlanToMissionItems (flightplan_t *fp) |
| void | apConvertMissionItemsToPlan (uint16_t size, mavlink_mission_item_t items[], flightplan_t *fp) |
| bool | IntfServiceHandler (mavlink_message_t *message) |
Variables | |
| EXTERN appdataInt_t | appdataInt |
| global variable containing app state | |
| EXTERN flightplan_t | fpdata |
| waypoint message | |
| EXTERN missionItemReached_t | wpreached |
| mission item reached | |
| EXTERN geofence_t | gfdata |
| geofence data | |
| EXTERN argsCmd_t | startMission |
| start mission command | |
| EXTERN noArgsCmd_t | resetIcarous |
| reset icarous command | |
| EXTERN object_t | traffic |
| traffic message | |
| EXTERN position_t | position |
| position message | |
| EXTERN local_position_t | local_position |
| local position message | |
| EXTERN attitude_t | attitude |
| attitude message | |
| EXTERN battery_status_t | battery_status |
| battery status message | |
| EXTERN cmdAck_t | ack |
| command acknowledge message | |
| EXTERN vfrhud_t | vfrhud |
| vfr hud data | |
| EXTERN rc_channels_t | rc_channels |
| rc channels | |
| EXTERN home_position_t | home_position |
| home position | |
| enum controlMode_e |
| void ARDUCOPTER_AppCleanUp | ( | void | ) |
Clean up variables
| void ARDUCOPTER_AppInit | ( | void | ) |
Initialize app properties
| void ARDUCOPTER_AppInitializeData | ( | void | ) |
Initialize app data
| void ARDUCOPTER_AppMain | ( | void | ) |
Entry point for app
| void ARDUCOPTER_ProcessPacket | ( | void | ) |
Process SB messages from pipes and take action
| int32_t ArducopterTableValidationFunc | ( | void * | TblPtr | ) |
Validate table data
| *TblPtr | pointer to table |
| int GetMAVLinkMsgFromAP | ( | void | ) |
Get mavlink message from Arducopter
| void ProcessAPMessage | ( | mavlink_message_t | message | ) |
Process mavlink message from arducopter and take action
| message | mavlink message |
| void Task1 | ( | void | ) |
Read from Arducopter data stream and pass data to groundstation and ICAROUS app