Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
waypoints.c
Go to the documentation of this file.
1/*
2 * Copyright (C) 2015 Lodewijk Sikkel <l.n.c.sikkel@tudelft.nl>
3 *
4 * This file is part of paparazzi.
5 *
6 * paparazzi is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License as published by
8 * the Free Software Foundation; either version 2, or (at your option)
9 * any later version.
10 *
11 * paparazzi is distributed in the hope that it will be useful,
12 * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 * GNU General Public License for more details.
15 *
16 * You should have received a copy of the GNU General Public License
17 * along with paparazzi; see the file COPYING. If not, write to
18 * the Free Software Foundation, 59 Temple Place - Suite 330,
19 * Boston, MA 02111-1307, USA.
20 *
21 */
22
29// Include own header
33
34// include mavlink headers, but ignore some warnings
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
40
41#include "generated/flight_plan.h"
42
43
45//#include "modules/nav/common_nav.h" // for fixed-wing aircraft
46
48
50{
51 if (seq < NB_WAYPOINT) { // Due to indexing
52#ifdef FIXEDWING_FIRMWARE
53 /* for fixedwing firmware send as LOCAL_ENU for now */
55 sysid,
56 compid,
57 seq,
60 0, // current
61 0, // autocontinue
62 0, 0, 0, 0, // params
67#else
68 /* for rotorcraft firmware use waypoint API and send as lat/lon */
69 /* sending lat/lon as float is actually a bad idea,
70 * but it seems that most GCSs don't understand the MISSION_ITEM_INT
71 */
72 struct LlaCoor_i *lla = waypoint_get_lla(seq);
74 sysid,
75 compid,
76 seq,
79 0, // current
80 0, // autocontinue
81 0, 0, 0, 0, // params
82 (float)lla->lat / 1e7,
83 (float)lla->lon / 1e7,
84 (float)lla->alt / 1e3,
86#endif
88 MAVLINK_DEBUG("Sent MISSION_ITEM message with seq %i\n", seq);
89 } else {
90 MAVLINK_DEBUG("ERROR: Wp index %i out of bounds\n", seq);
91 }
92}
93
95{
96 switch (msg->msgid) {
97
98 /* request for mission list, answer with number of waypoints */
100 MAVLINK_DEBUG("Received MISSION_REQUEST_LIST message\n");
103 if (mission_request_list_msg.target_system == mavlink_system.sysid) {
105 if (NB_WAYPOINT > 0) {
107 MAVLINK_DEBUG("State: %d\n", mission_mgr.state);
108 mission_mgr.seq = 0;
109 mission_mgr.rem_sysid = msg->sysid;
110 mission_mgr.rem_compid = msg->compid;
111 }
114
115 // Register the timeout timer (it is continuous so it needs to be cancelled after triggering)
117 } else {
118 // TODO: Handle case when the state is not IDLE
119 }
120 }
121 break;
122 }
123
124 /* request for mission item, answer with waypoint */
128 MAVLINK_DEBUG("Received MISSION_REQUEST message with seq %i\n", req.seq);
129
130 if (req.target_system != mavlink_system.sysid || req.seq >= NB_WAYPOINT) {
131 return;
132 }
133 /* Send if:
134 * - the first waypoint
135 * - current waypoint requested again
136 * - or next waypoint requested
137 */
138 if ((mission_mgr.state == STATE_SEND_LIST && req.seq == 0) ||
139 (mission_mgr.state == STATE_SEND_ITEM && (req.seq == mission_mgr.seq ||
140 req.seq == mission_mgr.seq + 1))) {
141 // Cancel the timeout timer
143
145 MAVLINK_DEBUG("State: %d\n", mission_mgr.state);
146 mission_mgr.seq = req.seq;
147
148 mavlink_send_wp(msg->sysid, msg->compid, mission_mgr.seq);
149
150 // Register the timeout timer
152 } else {
153 // TODO: Handle cases for which the above condition does not hold
154 }
155 break;
156 }
157
158#ifndef AP
159 /* change waypoints: only available when using waypoint API (rotorcraft firmware)
160 * This uses the waypoint_set_x functions (opposed to waypoint_move_x),
161 * meaning it doesn't send WP_MOVED Paparazzi messages.
162 */
163
164 /* initiate mission/waypoint write transaction */
168 if (mission_count.target_system != mavlink_system.sysid) {
169 return;
170 }
171 MAVLINK_DEBUG("Received MISSION_COUNT message with count %i\n", mission_count.count);
172 /* only allow new waypoint update transaction if currently idle */
174 MAVLINK_DEBUG("MISSION_COUNT error: mission manager not idle.\n");
175 return;
176 }
177 if (mission_count.count != NB_WAYPOINT) {
178 MAVLINK_DEBUG("MISSION_COUNT error: request writing %i instead of %i waypoints\n",
180 return;
181 }
182 /* valid initiation of waypoint write transaction, ask for first waypoint */
183 MAVLINK_DEBUG("MISSION_COUNT: Requesting first waypoint\n");
186
187 mission_mgr.seq = 0;
189
190 // Register the timeout timer
192 }
193 break;
194
195 /* got MISSION_ITEM, update one waypoint if in valid transaction */
199
200 if (mission_item.target_system != mavlink_system.sysid) {
201 return;
202 }
203
204 MAVLINK_DEBUG("Received MISSION_ITEM message with seq %i and frame %i\n",
205 mission_item.seq, mission_item.frame);
206
207 /* reject non waypoint updates */
208 if (mission_item.command != MAV_CMD_NAV_WAYPOINT ||
209 mission_item.seq >= NB_WAYPOINT) {
210 MAVLINK_DEBUG("rejected MISSION_ITEM command %i, seq %i\n",
211 mission_item.command, mission_item.seq);
212 return;
213 }
214
215 /* Only accept mission item in IDLE (update single waypoint) or in write transaction */
217 MAVLINK_DEBUG("got MISSION_ITEM while not in waypoint write transaction or idle\n");
218 return;
219 }
220 /* If in write transaction, only handle mission item if correct sequence */
222 MAVLINK_DEBUG("MISSION_ITEM, got waypoint seq %i, but requested %i\n",
224 return;
225 }
226
227 if (mission_item.frame == MAV_FRAME_GLOBAL) {
228 MAVLINK_DEBUG("MISSION_ITEM, global wp: lat=%f, lon=%f, alt=%f\n",
230 struct LlaCoor_i lla;
231 lla.lat = mission_item.x * 1e7; // lattitude in degrees*1e7
232 lla.lon = mission_item.y * 1e7; // longitude in degrees*1e7
233 lla.alt = mission_item.z * 1e3; // altitude in millimeters
235 }
237 MAVLINK_DEBUG("MISSION_ITEM, global_rel_alt wp: lat=%f, lon=%f, relative alt=%f\n",
239 struct LlaCoor_i lla;
240 lla.lat = mission_item.x * 1e7; // lattitude in degrees*1e7
241 lla.lon = mission_item.y * 1e7; // longitude in degrees*1e7
242 lla.alt = stateGetHmslOrigin_i() + mission_item.z * 1e3; // altitude in millimeters
244 }
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",
248 struct EnuCoor_f enu;
249 enu.x = mission_item.x;
250 enu.y = mission_item.y;
251 enu.z = mission_item.z;
253 }
254 else {
255 MAVLINK_DEBUG("No handler for MISSION_ITEM with frame %i\n", mission_item.frame);
256 return;
257 }
258 // acknowledge transmission single waypoint update
260 MAVLINK_DEBUG("Acknowledge single waypoint update\n");
265 }
266 // or end of transaction
267 else if (mission_item.seq == NB_WAYPOINT -1) {
268 MAVLINK_DEBUG("Acknowledging end of waypoint write transaction\n");
274 }
275 // or request next waypoint if still in middle of transaction
276 else {
277 MAVLINK_DEBUG("Requesting waypoint %i\n", mission_item.seq + 1);
281 mission_mgr.seq = mission_item.seq + 1;
283 }
284 break;
285 }
286
290
291 if (mission_item.target_system == mavlink_system.sysid) {
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) {
295 return;
296 }
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",
300 struct LlaCoor_i lla;
301 lla.lat = mission_item.x; // lattitude in degrees*1e7
302 lla.lon = mission_item.y; // longitude in degrees*1e7
303 lla.alt = mission_item.z * 1e3; // altitude in millimeters
308 }
309 else {
310 MAVLINK_DEBUG("No handler for MISSION_ITEM_INT with frame %i\n", mission_item.frame);
311 return;
312 }
313 }
314 }
315 break;
316#endif // AP
317
318 default:
319 break;
320 }
321}
#define WaypointX(_wp)
Definition common_nav.h:45
#define WaypointAlt(_wp)
waypoint altitude in m above MSL
Definition common_nav.h:48
#define WaypointY(_wp)
Definition common_nav.h:46
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)
Definition state.c:190
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
uint16_t foo
Definition main_demo5.c:58
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_SEND_LIST
@ STATE_WAYPOINT_WRITE_TRANSACTION
@ STATE_SEND_ITEM
@ STATE_IDLE
struct LlaCoor_i * waypoint_get_lla(uint8_t wp_id)
Get LLA coordinates of waypoint.
Definition waypoints.c:374
void waypoint_set_lla(uint8_t wp_id, struct LlaCoor_i *lla)
Definition waypoints.c:243
void waypoint_set_enu(uint8_t wp_id, struct EnuCoor_f *enu)
Set local ENU waypoint coordinates.
Definition waypoints.c:177
static int seq
Definition nps_ivy.c:32
float x
in meters
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.