13#include "cfe_platform_cfg.h"
18#include <network_includes.h>
21#include <arducopter_version.h>
33#include <sch_msgids.h>
34#include <mavlink/ardupilotmega/mavlink.h>
37#define ARDUCOPTER_PIPE_NAME "FLIGHTPLAN"
38#define ARDUCOPTER_PIPE_DEPTH 100
40#define SCH_ARDUCOPTER_PIPE1_NAME "SCH_ARDUCOPTER"
86 CFE_SB_PipeId_t INTERFACE_Pipe;
90 CFE_SB_PipeId_t SchInterface_Pipe;
91 CFE_SB_MsgPtr_t INTERFACEMsgPtr;
92 CFE_SB_MsgPtr_t Sch_MsgPtr;
93 CFE_TBL_Handle_t INTERFACE_tblHandle;
102 int waypoint_index[MAX_WAYPOINTS];
107 bool startWPDownlink;
110 uint16_t fenceVertices[MAX_GEOFENCES];
111 uint16_t numUplinkWaypoints;
112 uint16_t numDownlinkWaypoints;
113 uint16_t downlinkRequestIndex;
116 mavlink_mission_item_t UplinkMissionItems[MAX_WAYPOINTS];
117 mavlink_mission_item_t DownlinkMissionItems[MAX_WAYPOINTS];
121 mavlink_mission_item_t ReceivedMissionItems[MAX_WAYPOINTS];
125 param_t storedparams[PARAM_COUNT];
135 bool sentDefaultParams;
189void apSendHeartbeat(
void);
191void apSendCallsign(
void);
193void ap_gfCallback(uint32_t timer);
195void ap_pmCallback(uint32_t timerId);
197void ap_tjCallback(uint32_t timerId);
200void ap_startTimer(uint32_t *timerID,
void (*f)(uint32_t),
char* name,uint32_t startTime,uint32_t intvl);
202void ap_stopTimer(uint32_t *timerID);
204void apInterface_PublishParams(
void);
214void apConvertMissionItemsToPlan(uint16_t size,mavlink_mission_item_t items[],
flightplan_t *fp);
216bool IntfServiceHandler(mavlink_message_t *message);
EXTERN flightplan_t fpdata
waypoint message
Definition: arducopter.h:219
EXTERN home_position_t home_position
home position
Definition: arducopter.h:232
EXTERN argsCmd_t startMission
start mission command
Definition: arducopter.h:222
EXTERN cmdAck_t ack
command acknowledge message
Definition: arducopter.h:229
void ARDUCOPTER_AppMain(void)
Definition: arducopter.c:22
void ARDUCOPTER_AppCleanUp(void)
Definition: arducopter.c:242
int32_t ArducopterTableValidationFunc(void *TblPtr)
Definition: arducopter.c:246
EXTERN vfrhud_t vfrhud
vfr hud data
Definition: arducopter.h:230
controlMode_e
enumeration for Arducopter control modes
Definition: arducopter.h:61
@ RTL
automatic return to launching point
Definition: arducopter.h:68
@ STABILIZE
manual airframe angle with manual throttle
Definition: arducopter.h:62
@ GUIDED
fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
Definition: arducopter.h:66
@ LOITER
automatic horizontal acceleration with automatic throttle
Definition: arducopter.h:67
@ AVOID_ADSB
automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft
Definition: arducopter.h:77
@ ALT_HOLD
manual airframe angle with automatic throttle
Definition: arducopter.h:64
@ GUIDED_NOGPS
guided mode but only accepts attitude and altitude
Definition: arducopter.h:78
@ POSHOLD
automatic position hold with manual override, with automatic throttle
Definition: arducopter.h:74
@ AUTOTUNE
automatically tune the vehicle's roll and pitch gains
Definition: arducopter.h:73
@ BRAKE
full-brake using inertial/GPS system, no pilot input
Definition: arducopter.h:75
@ DRIFT
semi-automous position, yaw and throttle control
Definition: arducopter.h:70
@ SPORT
manual earth-frame angular rate control with manual throttle
Definition: arducopter.h:71
@ FLIP
automatically flip the vehicle on the roll axis
Definition: arducopter.h:72
@ CIRCLE
automatic circular flight with automatic throttle
Definition: arducopter.h:69
@ THROW
throw to launch mode using inertial/GPS system, no pilot input
Definition: arducopter.h:76
@ ACRO
manual body-frame angular rate with manual throttle
Definition: arducopter.h:63
@ AUTO
fully automatic waypoint control using mission commands
Definition: arducopter.h:65
EXTERN rc_channels_t rc_channels
rc channels
Definition: arducopter.h:231
void ProcessAPMessage(mavlink_message_t message)
Definition: apProcessMessages.c:53
EXTERN position_t position
position message
Definition: arducopter.h:225
EXTERN appdataInt_t appdataInt
global variable containing app state
Definition: arducopter.h:218
EXTERN attitude_t attitude
attitude message
Definition: arducopter.h:227
EXTERN geofence_t gfdata
geofence data
Definition: arducopter.h:221
EXTERN local_position_t local_position
local position message
Definition: arducopter.h:226
int GetMAVLinkMsgFromAP(void)
Definition: apProcessMessages.c:12
EXTERN battery_status_t battery_status
battery status message
Definition: arducopter.h:228
EXTERN missionItemReached_t wpreached
mission item reached
Definition: arducopter.h:220
void ARDUCOPTER_ProcessPacket(void)
Definition: apProcessMessages.c:780
void ARDUCOPTER_AppInitializeData(void)
Definition: arducopter.c:190
void ARDUCOPTER_AppInit(void)
Definition: arducopter.c:85
EXTERN object_t traffic
traffic message
Definition: arducopter.h:224
EXTERN noArgsCmd_t resetIcarous
reset icarous command
Definition: arducopter.h:223
Event definitions for arducopter app.
ArduCopter app table definition.
Defintion of messages used by geofence_msg.h.
Defines message topics published by the geofence application.
Defines message topics used by the guidance application.
serial/socket port library
Input parameters for ardupilot application.
Definition: arducopter_table.h:15
Structure to hold app data.
Definition: apInterface.h:47
uint8_t runThreads
thread active status
Definition: arducopter.h:96
CFE_SB_PipeId_t Band_Pipe
pipe variable
Definition: arducopter.h:89
int recvGeofIndex
Index of geofence being received.
Definition: arducopter.h:108
int receivingWP
waypoint current being received
Definition: arducopter.h:124
CFE_SB_PipeId_t Traffic_Pipe
pipe variable
Definition: arducopter.h:88
int numGeofences
Number of geofences.
Definition: arducopter.h:100
uint32_t mutex_read
mutex id
Definition: arducopter.h:104
int numWaypoints
num total waypoints
Definition: arducopter.h:97
int nextWaypointIndex
Next waypoint index to goto.
Definition: arducopter.h:99
uint32_t mutex_write
mutex id
Definition: arducopter.h:105
int * waypoint_type
waypoint type description
Definition: arducopter.h:101
int foundUAV
UAV communication alive.
Definition: arducopter.h:103
CFE_SB_PipeId_t Command_Pipe
pipe variable
Definition: arducopter.h:87
int waypointSeq
received position waypoint
Definition: arducopter.h:98
Command with arguments.
Definition: Icarous_msg.h:244
aircraft attitude information.
Definition: Icarous_msg.h:219
Message containing battery status.
Definition: Icarous_msg.h:297
Definition: Icarous_msg.h:35
Definition: icarous_utils.c:58
Command acknowledgement.
Definition: Icarous_msg.h:258
message encoding flight plan information
message encoding geofence vertex information.
Definition: Icarous_msg.h:139
Definition: Icarous_msg.h:322
aircraft local position information.
Definition: Icarous_msg.h:199
message indicating a specific waypoint has been reached.
Definition: Icarous_msg.h:127
Command without arguments.
Definition: Icarous_msg.h:235
message to represent information about an static/dynamic object
Definition: Icarous_msg.h:154
Structure to hold port attributes.
Definition: port_lib.h:37
position information of aircraft.
Definition: Icarous_msg.h:174
Message containing rc channel information.
Definition: Icarous_msg.h:314
Definition: Icarous_msg.h:279
Traffic message definition.
Traffic message id definitions.
definition of messages generated by the trajectory messages
definition of message ids relevant to the trajectory applicaiton