35 #pragma GCC diagnostic push
36 #pragma GCC diagnostic ignored "-Wswitch-default"
37 #include "mavlink/paparazzi/mavlink.h"
38 #pragma GCC diagnostic pop
40 #include "generated/flight_plan.h"
50 if (
seq < NB_WAYPOINT) {
53 mavlink_msg_mission_item_send(MAVLINK_COMM_0,
71 mavlink_msg_mission_item_send(MAVLINK_COMM_0,
80 (
float)lla->
lat / 1e7,
81 (
float)lla->
lon / 1e7,
82 (
float)lla->
alt / 1e3);
96 case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: {
98 mavlink_mission_request_list_t mission_request_list_msg;
99 mavlink_msg_mission_request_list_decode(
msg, &mission_request_list_msg);
100 if (mission_request_list_msg.target_system ==
mavlink_system.sysid) {
102 if (NB_WAYPOINT > 0) {
109 mavlink_msg_mission_count_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid, NB_WAYPOINT);
122 case MAVLINK_MSG_ID_MISSION_REQUEST: {
123 mavlink_mission_request_t req;
124 mavlink_msg_mission_request_decode(
msg, &req);
125 MAVLINK_DEBUG(
"Received MISSION_REQUEST message with seq %i\n", req.seq);
127 if (req.target_system !=
mavlink_system.sysid || req.seq >= NB_WAYPOINT) {
162 case MAVLINK_MSG_ID_MISSION_COUNT: {
163 mavlink_mission_count_t mission_count;
164 mavlink_msg_mission_count_decode(
msg, &mission_count);
168 MAVLINK_DEBUG(
"Received MISSION_COUNT message with count %i\n", mission_count.count);
171 MAVLINK_DEBUG(
"MISSION_COUNT error: mission manager not idle.\n");
174 if (mission_count.count != NB_WAYPOINT) {
175 MAVLINK_DEBUG(
"MISSION_COUNT error: request writing %i instead of %i waypoints\n",
176 mission_count.count, NB_WAYPOINT);
181 mavlink_msg_mission_request_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid, 0);
193 case MAVLINK_MSG_ID_MISSION_ITEM: {
194 mavlink_mission_item_t mission_item;
195 mavlink_msg_mission_item_decode(
msg, &mission_item);
201 MAVLINK_DEBUG(
"Received MISSION_ITEM message with seq %i and frame %i\n",
202 mission_item.seq, mission_item.frame);
205 if (mission_item.command != MAV_CMD_NAV_WAYPOINT ||
206 mission_item.seq >= NB_WAYPOINT) {
208 mission_item.command, mission_item.seq);
214 MAVLINK_DEBUG(
"got MISSION_ITEM while not in waypoint write transaction or idle\n");
219 MAVLINK_DEBUG(
"MISSION_ITEM, got waypoint seq %i, but requested %i\n",
224 if (mission_item.frame == MAV_FRAME_GLOBAL) {
225 MAVLINK_DEBUG(
"MISSION_ITEM, global wp: lat=%f, lon=%f, alt=%f\n",
226 mission_item.x, mission_item.y, mission_item.z);
228 lla.
lat = mission_item.x * 1e7;
229 lla.
lon = mission_item.y * 1e7;
230 lla.
alt = mission_item.z * 1e3;
233 else if (mission_item.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT) {
234 MAVLINK_DEBUG(
"MISSION_ITEM, global_rel_alt wp: lat=%f, lon=%f, relative alt=%f\n",
235 mission_item.x, mission_item.y, mission_item.z);
237 lla.
lat = mission_item.x * 1e7;
238 lla.
lon = mission_item.y * 1e7;
242 else if (mission_item.frame == MAV_FRAME_LOCAL_ENU) {
243 MAVLINK_DEBUG(
"MISSION_ITEM, local_enu wp: x=%f, y=%f, z=%f\n",
244 mission_item.x, mission_item.y, mission_item.z);
246 enu.
x = mission_item.x;
247 enu.
y = mission_item.y;
248 enu.
z = mission_item.z;
252 MAVLINK_DEBUG(
"No handler for MISSION_ITEM with frame %i\n", mission_item.frame);
258 mavlink_msg_mission_ack_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
259 MAV_MISSION_ACCEPTED);
264 else if (mission_item.seq == NB_WAYPOINT -1) {
265 MAVLINK_DEBUG(
"Acknowledging end of waypoint write transaction\n");
266 mavlink_msg_mission_ack_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
267 MAV_MISSION_ACCEPTED);
274 MAVLINK_DEBUG(
"Requesting waypoint %i\n", mission_item.seq + 1);
275 mavlink_msg_mission_request_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
276 mission_item.seq + 1);
284 case MAVLINK_MSG_ID_MISSION_ITEM_INT: {
285 mavlink_mission_item_int_t mission_item;
286 mavlink_msg_mission_item_int_decode(
msg, &mission_item);
289 MAVLINK_DEBUG(
"Received MISSION_ITEM_INT message with seq %i and frame %i\n",
290 mission_item.seq, mission_item.frame);
291 if (mission_item.seq >= NB_WAYPOINT) {
294 if (mission_item.frame == MAV_FRAME_GLOBAL_INT) {
295 MAVLINK_DEBUG(
"MISSION_ITEM_INT, global_int wp: lat=%i, lon=%i, alt=%f\n",
296 mission_item.x, mission_item.y, mission_item.z);
298 lla.
lat = mission_item.x;
299 lla.
lon = mission_item.y;
300 lla.
alt = mission_item.z * 1e3;
302 mavlink_msg_mission_ack_send(MAVLINK_COMM_0,
msg->sysid,
msg->compid,
303 MAV_MISSION_ACCEPTED);
307 MAVLINK_DEBUG(
"No handler for MISSION_ITEM_INT with frame %i\n", mission_item.frame);