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"
51 if (
seq < NB_WAYPOINT) {
52 #ifdef FIXEDWING_FIRMWARE
54 mavlink_msg_mission_item_send(MAVLINK_COMM_0,
66 MAV_MISSION_TYPE_MISSION);
73 mavlink_msg_mission_item_send(MAVLINK_COMM_0,
82 (
float)lla->
lat / 1e7,
83 (
float)lla->
lon / 1e7,
84 (
float)lla->
alt / 1e3,
85 MAV_MISSION_TYPE_MISSION);
99 case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: {
101 mavlink_mission_request_list_t mission_request_list_msg;
102 mavlink_msg_mission_request_list_decode(
msg, &mission_request_list_msg);
103 if (mission_request_list_msg.target_system ==
mavlink_system.sysid) {
105 if (NB_WAYPOINT > 0) {
112 mavlink_msg_mission_count_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid, NB_WAYPOINT, MAV_MISSION_TYPE_MISSION);
125 case MAVLINK_MSG_ID_MISSION_REQUEST: {
126 mavlink_mission_request_t req;
127 mavlink_msg_mission_request_decode(
msg, &req);
128 MAVLINK_DEBUG(
"Received MISSION_REQUEST message with seq %i\n", req.seq);
130 if (req.target_system !=
mavlink_system.sysid || req.seq >= NB_WAYPOINT) {
165 case MAVLINK_MSG_ID_MISSION_COUNT: {
166 mavlink_mission_count_t mission_count;
167 mavlink_msg_mission_count_decode(
msg, &mission_count);
171 MAVLINK_DEBUG(
"Received MISSION_COUNT message with count %i\n", mission_count.count);
174 MAVLINK_DEBUG(
"MISSION_COUNT error: mission manager not idle.\n");
177 if (mission_count.count != NB_WAYPOINT) {
178 MAVLINK_DEBUG(
"MISSION_COUNT error: request writing %i instead of %i waypoints\n",
179 mission_count.count, NB_WAYPOINT);
184 mavlink_msg_mission_request_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid, 0, MAV_MISSION_TYPE_MISSION);
196 case MAVLINK_MSG_ID_MISSION_ITEM: {
197 mavlink_mission_item_t mission_item;
198 mavlink_msg_mission_item_decode(
msg, &mission_item);
204 MAVLINK_DEBUG(
"Received MISSION_ITEM message with seq %i and frame %i\n",
205 mission_item.seq, mission_item.frame);
208 if (mission_item.command != MAV_CMD_NAV_WAYPOINT ||
209 mission_item.seq >= NB_WAYPOINT) {
211 mission_item.command, mission_item.seq);
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",
227 if (mission_item.frame == MAV_FRAME_GLOBAL) {
228 MAVLINK_DEBUG(
"MISSION_ITEM, global wp: lat=%f, lon=%f, alt=%f\n",
229 mission_item.x, mission_item.y, mission_item.z);
231 lla.
lat = mission_item.x * 1e7;
232 lla.
lon = mission_item.y * 1e7;
233 lla.
alt = mission_item.z * 1e3;
236 else if (mission_item.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT) {
237 MAVLINK_DEBUG(
"MISSION_ITEM, global_rel_alt wp: lat=%f, lon=%f, relative alt=%f\n",
238 mission_item.x, mission_item.y, mission_item.z);
240 lla.
lat = mission_item.x * 1e7;
241 lla.
lon = mission_item.y * 1e7;
245 else if (mission_item.frame == MAV_FRAME_LOCAL_ENU) {
246 MAVLINK_DEBUG(
"MISSION_ITEM, local_enu wp: x=%f, y=%f, z=%f\n",
247 mission_item.x, mission_item.y, mission_item.z);
249 enu.
x = mission_item.x;
250 enu.
y = mission_item.y;
251 enu.
z = mission_item.z;
255 MAVLINK_DEBUG(
"No handler for MISSION_ITEM with frame %i\n", mission_item.frame);
261 mavlink_msg_mission_ack_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
262 MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION);
267 else if (mission_item.seq == NB_WAYPOINT -1) {
268 MAVLINK_DEBUG(
"Acknowledging end of waypoint write transaction\n");
269 mavlink_msg_mission_ack_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
270 MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION);
277 MAVLINK_DEBUG(
"Requesting waypoint %i\n", mission_item.seq + 1);
278 mavlink_msg_mission_request_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
279 mission_item.seq + 1, MAV_MISSION_TYPE_MISSION);
287 case MAVLINK_MSG_ID_MISSION_ITEM_INT: {
288 mavlink_mission_item_int_t mission_item;
289 mavlink_msg_mission_item_int_decode(
msg, &mission_item);
292 MAVLINK_DEBUG(
"Received MISSION_ITEM_INT message with seq %i and frame %i\n",
293 mission_item.seq, mission_item.frame);
294 if (mission_item.seq >= NB_WAYPOINT) {
297 if (mission_item.frame == MAV_FRAME_GLOBAL_INT) {
298 MAVLINK_DEBUG(
"MISSION_ITEM_INT, global_int wp: lat=%i, lon=%i, alt=%f\n",
299 mission_item.x, mission_item.y, mission_item.z);
301 lla.
lat = mission_item.x;
302 lla.
lon = mission_item.y;
303 lla.
alt = mission_item.z * 1e3;
305 mavlink_msg_mission_ack_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
306 MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION);
310 MAVLINK_DEBUG(
"No handler for MISSION_ITEM_INT with frame %i\n", mission_item.frame);
#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.