35#pragma GCC diagnostic push
36#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
37#pragma GCC diagnostic ignored "-Wswitch-default"
38#include "mavlink/ardupilotmega/mavlink.h"
39#pragma GCC diagnostic pop
41#include "generated/flight_plan.h"
52#ifdef FIXEDWING_FIRMWARE
82 (
float)lla->
lat / 1
e7,
83 (
float)lla->
lon / 1
e7,
84 (
float)lla->
alt / 1
e3,
128 MAVLINK_DEBUG(
"Received MISSION_REQUEST message with seq %i\n", req.seq);
174 MAVLINK_DEBUG(
"MISSION_COUNT error: mission manager not idle.\n");
178 MAVLINK_DEBUG(
"MISSION_COUNT error: request writing %i instead of %i waypoints\n",
204 MAVLINK_DEBUG(
"Received MISSION_ITEM message with seq %i and frame %i\n",
217 MAVLINK_DEBUG(
"got MISSION_ITEM while not in waypoint write transaction or idle\n");
222 MAVLINK_DEBUG(
"MISSION_ITEM, got waypoint seq %i, but requested %i\n",
228 MAVLINK_DEBUG(
"MISSION_ITEM, global wp: lat=%f, lon=%f, alt=%f\n",
237 MAVLINK_DEBUG(
"MISSION_ITEM, global_rel_alt wp: lat=%f, lon=%f, relative alt=%f\n",
246 MAVLINK_DEBUG(
"MISSION_ITEM, local_enu wp: x=%f, y=%f, z=%f\n",
268 MAVLINK_DEBUG(
"Acknowledging end of waypoint write transaction\n");
292 MAVLINK_DEBUG(
"Received MISSION_ITEM_INT message with seq %i and frame %i\n",
298 MAVLINK_DEBUG(
"MISSION_ITEM_INT, global_int wp: lat=%i, lon=%i, alt=%f\n",
#define WaypointAlt(_wp)
waypoint altitude in m above MSL
static void mavlink_send_wp(uint8_t sysid, uint8_t compid, uint16_t seq)
void mavlink_wp_message_handler(const mavlink_message_t *msg)
int32_t lat
in degrees*1e7
int32_t alt
in millimeters above WGS84 reference ellipsoid
int32_t lon
in degrees*1e7
vector in Latitude, Longitude and Altitude
int32_t stateGetHmslOrigin_i(void)
Get the HMSL of the frame origin (int)
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
mavlink_system_t mavlink_system
mavlink_mission_mgr mission_mgr
Basic MAVLink datalink implementation.
#define MAVLINK_DEBUG(...)
#define MAVLinkSendMessage()
void mavlink_mission_set_timer(void)
void mavlink_mission_cancel_timer(void)
Common functions used within the mission library, blocks and waypoints cannot be send simultaneously ...
enum MAVLINK_MISSION_MGR_STATES state
@ STATE_WAYPOINT_WRITE_TRANSACTION
struct LlaCoor_i * waypoint_get_lla(uint8_t wp_id)
Get LLA coordinates of waypoint.
void waypoint_set_lla(uint8_t wp_id, struct LlaCoor_i *lla)
void waypoint_set_enu(uint8_t wp_id, struct EnuCoor_f *enu)
Set local ENU waypoint coordinates.
vector in East North Up coordinates Units: meters
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.