UASWaypointManager.cc 38 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2
/*=====================================================================

lm's avatar
lm committed
3
QGroundControl Open Source Ground Control Station
pixhawk's avatar
pixhawk committed
4

Lorenz Meier's avatar
Lorenz Meier committed
5
(c) 2009-2012 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
6

lm's avatar
lm committed
7
This file is part of the QGROUNDCONTROL project
pixhawk's avatar
pixhawk committed
8

lm's avatar
lm committed
9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12 13
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

lm's avatar
lm committed
14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17 18 19
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
lm's avatar
lm committed
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25 26 27 28 29 30 31

======================================================================*/

/**
 * @file
 *   @brief Implementation of the waypoint protocol handler
 *
 *   @author Petri Tanskanen <mavteam@student.ethz.ch>
 *
 */

32 33
#include "UASWaypointManager.h"
#include "UAS.h"
34
#include "mavlink_types.h"
35
#include "UASManager.h"
36
#include "QGCMessageBox.h"
37

38
#define PROTOCOL_TIMEOUT_MS 2000    ///< maximum time to wait for pending messages until timeout
lm's avatar
lm committed
39 40
#define PROTOCOL_DELAY_MS 20        ///< minimum delay between sent messages
#define PROTOCOL_MAX_RETRIES 5      ///< maximum number of send retries (after timeout)
41
const float UASWaypointManager::defaultAltitudeHomeOffset   = 30.0f;
lm's avatar
lm committed
42
UASWaypointManager::UASWaypointManager(UAS* _uas)
43 44 45 46 47 48 49
    : uas(_uas),
      current_retries(0),
      current_wp_id(0),
      current_count(0),
      current_state(WP_IDLE),
      current_partner_systemid(0),
      current_partner_compid(0),
50
      currentWaypointEditable(),
51
      protocol_timer(this)
pixhawk's avatar
pixhawk committed
52
{
53 54
    _offlineEditingModeMessage = tr("You are in offline editing mode. Make sure to save your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect.");
    
55 56
    if (uas)
    {
lm's avatar
lm committed
57 58 59
        uasid = uas->getUASID();
        connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout()));
        connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64)));
60
        connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,quint64)));
lm's avatar
lm committed
61 62 63 64
    }
    else
    {
        uasid = 0;
65
    }
66 67 68 69
    
    // We signal to ourselves here so that tiemrs are started and stopped on correct thread
    connect(this, SIGNAL(_startProtocolTimer(void)), this, SLOT(_startProtocolTimerOnThisThread(void)));
    connect(this, SIGNAL(_stopProtocolTimer(void)), this, SLOT(_stopProtocolTimerOnThisThread(void)));
pixhawk's avatar
pixhawk committed
70 71
}

LM's avatar
LM committed
72 73 74 75 76
UASWaypointManager::~UASWaypointManager()
{

}

pixhawk's avatar
pixhawk committed
77
void UASWaypointManager::timeout()
78
{
79
    if (current_retries > 0) {
80 81
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries--;
82
        emit updateStatusString(tr("Timeout, retrying (retries left: %1)").arg(current_retries));
83

84
        if (current_state == WP_GETLIST) {
85
            sendWaypointRequestList();
86
        } else if (current_state == WP_GETLIST_GETWPS) {
87
            sendWaypointRequest(current_wp_id);
88
        } else if (current_state == WP_SENDLIST) {
89
            sendWaypointCount();
90
        } else if (current_state == WP_SENDLIST_SENDWPS) {
91
            sendWaypoint(current_wp_id);
92
        } else if (current_state == WP_CLEARLIST) {
93
            sendWaypointClearAll();
94
        } else if (current_state == WP_SETCURRENT) {
95 96
            sendWaypointSetCurrent(current_wp_id);
        }
97
    } else {
98
        protocol_timer.stop();
pixhawk's avatar
pixhawk committed
99

100
        emit updateStatusString("Operation timed out.");
pixhawk's avatar
pixhawk committed
101

102 103 104 105
        current_state = WP_IDLE;
        current_count = 0;
        current_wp_id = 0;
    }
106 107
}

108 109 110 111
void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time)
{
    Q_UNUSED(mav);
    Q_UNUSED(time);
112
    if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU))
113
    {
pixhawk's avatar
pixhawk committed
114 115 116
        double xdiff = x-currentWaypointEditable->getX();
        double ydiff = y-currentWaypointEditable->getY();
        double zdiff = z-currentWaypointEditable->getZ();
117 118 119 120 121
        double dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
        emit waypointDistanceChanged(dist);
    }
}

122
void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double altAMSL, double altWGS84, quint64 time)
123
{
124 125
    Q_UNUSED(mav);
    Q_UNUSED(time);
126 127
    Q_UNUSED(altAMSL);
    Q_UNUSED(altWGS84);
128 129
	Q_UNUSED(lon);
	Q_UNUSED(lat);
130
    if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT))
131 132 133 134 135
    {
        // TODO FIXME Calculate distance
        double dist = 0;
        emit waypointDistanceChanged(dist);
    }
136 137
}

138 139
void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count)
{
140
    if (current_state == WP_GETLIST && systemId == current_partner_systemid) {
141
        emit _startProtocolTimer(); // Start timer on correct thread
142 143
        current_retries = PROTOCOL_MAX_RETRIES;

144 145
        //Clear the old edit-list before receiving the new one
        if (read_to_edit == true){
146
            while(waypointsEditable.count()>0) {
147
                Waypoint *t = waypointsEditable[0];
148
                waypointsEditable.removeAt(0);
149 150 151 152 153
                delete t;
            }
            emit waypointEditableListChanged();
        }

154
        if (count > 0) {
pixhawk's avatar
pixhawk committed
155 156 157 158
            current_count = count;
            current_wp_id = 0;
            current_state = WP_GETLIST_GETWPS;
            sendWaypointRequest(current_wp_id);
159
        } else {
160
            emit _stopProtocolTimer();  // Stop the time on our thread
161 162
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
163 164 165
            current_state = WP_IDLE;
            current_count = 0;
            current_wp_id = 0;
pixhawk's avatar
pixhawk committed
166
        }
167 168


169
    } else {
170
        qDebug("Rejecting waypoint count message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_GETLIST, current_partner_systemid, systemId, current_partner_compid, compId);
171
    }
172 173
}

lm's avatar
lm committed
174
void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp)
pixhawk's avatar
pixhawk committed
175
{
176
    if (systemId == current_partner_systemid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id) {
177
        emit _startProtocolTimer(); // Start timer on our thread
178 179
        current_retries = PROTOCOL_MAX_RETRIES;

180
        if(wp->seq == current_wp_id) {
pixhawk's avatar
pixhawk committed
181 182 183 184 185 186 187 188 189 190 191

            Waypoint *lwp_vo = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
            addWaypointViewOnly(lwp_vo);


            if (read_to_edit == true) {
                Waypoint *lwp_ed = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
                addWaypointEditable(lwp_ed, false);
                if (wp->current == 1) currentWaypointEditable = lwp_ed;
            }

pixhawk's avatar
pixhawk committed
192 193 194 195

            //get next waypoint
            current_wp_id++;

196
            if(current_wp_id < current_count) {
197
                sendWaypointRequest(current_wp_id);
198
            } else {
199 200
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
201
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
202 203 204
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
205

206
                emit _stopProtocolTimer(); // Stop timer on our thread
207
                emit readGlobalWPFromUAS(false);
208
                QTime time = QTime::currentTime();
209
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
210

pixhawk's avatar
pixhawk committed
211
            }
212
        } else {
213
            emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
214
        }
215 216 217 218 219 220 221 222 223 224
    } else if (systemId == current_partner_systemid
            && wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->getAction()) {
        // accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions
        // but only update view only side
        Waypoint *lwp_vo = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);

        waypointsViewOnly.replace(wp->seq, lwp_vo);
        emit waypointViewOnlyListChanged();
        emit waypointViewOnlyListChanged(uasid);

225
    } else {
226
        qDebug("Rejecting waypoint message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_GETLIST_GETWPS, current_partner_systemid, systemId, current_partner_compid, compId);
227
    }
pixhawk's avatar
pixhawk committed
228 229
}

lm's avatar
lm committed
230
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
231
{
232 233 234 235 236 237 238 239 240 241
    if (systemId != current_partner_systemid) {
        return;
    }

    // Check if the current partner component ID is generic. If it is, we might need to update
    if (current_partner_compid == MAV_COMP_ID_MISSIONPLANNER) {
        current_partner_compid = compId;
    }

    if (compId == current_partner_compid || compId == MAV_COMP_ID_ALL) {
242
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
243
            //all waypoints sent and ack received
244
            emit _stopProtocolTimer();  // Stop timer on our thread
245
            current_state = WP_IDLE;
246 247 248
            readWaypoints(false); //Update "Onboard Waypoints"-tab immediately after the waypoint list has been sent.
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
249 250
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281
            switch (wpa->type)
            {
            case MAV_MISSION_UNSUPPORTED_FRAME:
                emit updateStatusString(tr("ERROR: Coordinate frame unsupported."));
                break;
            case MAV_MISSION_UNSUPPORTED:
                emit updateStatusString(tr("ERROR: Unsupported command."));
                break;
            case MAV_MISSION_NO_SPACE:
                emit updateStatusString(tr("ERROR: Mission count exceeds storage."));
                break;
            case MAV_MISSION_INVALID:
            case MAV_MISSION_INVALID_PARAM1:
            case MAV_MISSION_INVALID_PARAM2:
            case MAV_MISSION_INVALID_PARAM3:
            case MAV_MISSION_INVALID_PARAM4:
            case MAV_MISSION_INVALID_PARAM5_X:
            case MAV_MISSION_INVALID_PARAM6_Y:
            case MAV_MISSION_INVALID_PARAM7:
                emit updateStatusString(tr("ERROR: A specified parameter was invalid."));
                break;
            case MAV_MISSION_INVALID_SEQUENCE:
                emit updateStatusString(tr("ERROR: Mission received out of sequence."));
                break;
            case MAV_MISSION_DENIED:
                emit updateStatusString(tr("ERROR: UAS not accepting missions."));
                break;
            case MAV_MISSION_ERROR:
            default:
                emit updateStatusString(tr("ERROR: Unspecified error"));
                break;
282
            }
283
            emit _stopProtocolTimer();  // Stop timer on our thread
284
            current_state = WP_IDLE;
285
        } else if(current_state == WP_CLEARLIST) {
286
            emit _stopProtocolTimer(); // Stop timer on our thread
287
            current_state = WP_IDLE;
288 289
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
290
        }
291 292 293
    }
}

lm's avatar
lm committed
294
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
295
{
296
    if (systemId == current_partner_systemid && ((current_state == WP_SENDLIST && wpr->seq == 0) || (current_state == WP_SENDLIST_SENDWPS && (wpr->seq == current_wp_id || wpr->seq == current_wp_id + 1)))) {
297
        emit _startProtocolTimer();  // Start timer on our thread
298
        current_retries = PROTOCOL_MAX_RETRIES;
299

300
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
301 302 303
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
304
        } else {
pixhawk's avatar
pixhawk committed
305 306
            //TODO: Error message or something
        }
307
    } else {
308
        qDebug("Rejecting waypoint request message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_SENDLIST_SENDWPS, current_partner_systemid, systemId, current_partner_compid, compId);
309
    }
310 311
}

lm's avatar
lm committed
312
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
313
{
314
	Q_UNUSED(compId);
lm's avatar
lm committed
315
    if (!uas) return;
316
    if (systemId == uasid) {
317
        emit updateStatusString(tr("Reached waypoint %1").arg(wpr->seq));
pixhawk's avatar
pixhawk committed
318
    }
pixhawk's avatar
pixhawk committed
319 320
}

lm's avatar
lm committed
321
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
322
{
323
    Q_UNUSED(compId);
lm's avatar
lm committed
324
    if (!uas) return;
325
    if (systemId == uasid) {
326
        // FIXME Petri
327
        if (current_state == WP_SETCURRENT) {
328
            emit _stopProtocolTimer();  // Stop timer on our thread
329
            current_state = WP_IDLE;
330 331

            // update the local main storage
pixhawk's avatar
pixhawk committed
332 333 334 335
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
                    if (waypointsViewOnly[i]->getId() == wpc->seq) {
                        waypointsViewOnly[i]->setCurrent(true);
336
                    } else {
pixhawk's avatar
pixhawk committed
337
                        waypointsViewOnly[i]->setCurrent(false);
338 339 340
                    }
                }
            }
341
        }
342
        emit updateStatusString(tr("New current waypoint %1").arg(wpc->seq));
343 344
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
345
    }
pixhawk's avatar
pixhawk committed
346 347
}

348
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
349
{
350
    // If only one waypoint was changed, emit only WP signal
351
    if (wp != NULL) {
352
        emit waypointEditableChanged(uasid, wp);
353
    } else {
354
        emit waypointEditableListChanged();
355
        emit waypointEditableListChanged(uasid);
356
    }
357 358
}

359 360 361
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
362
        emit waypointViewOnlyChanged(uasid, wp);
363 364
    } else {
        emit waypointViewOnlyListChanged();
365
        emit waypointViewOnlyListChanged(uasid);
366 367
    }
}
368 369


370
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
371
{
pixhawk's avatar
pixhawk committed
372
    if (seq < waypointsViewOnly.size()) {
373
        if(current_state == WP_IDLE) {
374

375
            //send change to UAS - important to note: if the transmission fails, we have inconsistencies
376
            emit _startProtocolTimer();  // Start timer on our thread
377 378 379 380
            current_retries = PROTOCOL_MAX_RETRIES;

            current_state = WP_SETCURRENT;
            current_wp_id = seq;
381
            current_partner_systemid = uasid;
lm's avatar
lm committed
382
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
383 384 385 386 387 388 389 390 391

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

392 393
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
394
    if (seq < waypointsEditable.count()) {
395 396
        if(current_state == WP_IDLE) {
            //update local main storage
397
            for (int i = 0; i < waypointsEditable.count(); i++) {
398 399 400 401 402 403 404 405 406 407 408 409
                if (waypointsEditable[i]->getId() == seq) {
                    waypointsEditable[i]->setCurrent(true);
                } else {
                    waypointsEditable[i]->setCurrent(false);
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
410 411 412 413

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
414
    {
pixhawk's avatar
pixhawk committed
415 416 417 418
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
419
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
420 421 422 423
    }
}


pixhawk's avatar
pixhawk committed
424
/**
425
 * @warning Make sure the waypoint stays valid for the whole application lifecycle!
pixhawk's avatar
pixhawk committed
426
 * @param enforceFirstActive Enforces that the first waypoint is set as active
427
 * @see createWaypoint() is more suitable for most use cases
pixhawk's avatar
pixhawk committed
428
 */
429
void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive)
430
{
lm's avatar
lm committed
431 432
    if (wp)
    {
433
        // Check if this is the first waypoint in an offline list
434 435 436
        if (waypointsEditable.count() == 0 && uas == NULL) {
            QGCMessageBox::critical(tr("Waypoint Manager"),  _offlineEditingModeMessage);
        }
437

438 439
        wp->setId(waypointsEditable.count());
        if (enforceFirstActive && waypointsEditable.count() == 0)
440 441
        {
            wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
442
            currentWaypointEditable = wp;
443
        }
444
        waypointsEditable.insert(waypointsEditable.count(), wp);
445
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
446

447
        emit waypointEditableListChanged();
448
        emit waypointEditableListChanged(uasid);
449
    }
pixhawk's avatar
pixhawk committed
450 451
}

452 453 454 455 456
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
457
    // Check if this is the first waypoint in an offline list
458 459 460
    if (waypointsEditable.count() == 0 && uas == NULL) {
        QGCMessageBox::critical(tr("Waypoint Manager"),  _offlineEditingModeMessage);
    }
461

462
    Waypoint* wp = new Waypoint();
463 464 465
    wp->setId(waypointsEditable.count());
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
466
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
467
    if (enforceFirstActive && waypointsEditable.count() == 0)
468 469
    {
        wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
470
        currentWaypointEditable = wp;
471
    }
472
    waypointsEditable.append(wp);
473
    connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
474

475
    emit waypointEditableListChanged();
476
    emit waypointEditableListChanged(uasid);
477 478 479
    return wp;
}

480
int UASWaypointManager::removeWaypoint(quint16 seq)
481
{
482
    if (seq < waypointsEditable.count())
483
    {
pixhawk's avatar
pixhawk committed
484
        Waypoint *t = waypointsEditable[seq];
485 486 487

        if (t->getCurrent() == true) //trying to remove the current waypoint
        {
488
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
489 490 491
            {
                waypointsEditable[seq+1]->setCurrent(true);
            }
492
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
493 494 495 496 497
            {
                waypointsEditable[seq-1]->setCurrent(true);
            }
        }

498
        waypointsEditable.removeAt(seq);
499
        delete t;
500
        t = NULL;
501

502
        for(int i = seq; i < waypointsEditable.count(); i++)
503
        {
pixhawk's avatar
pixhawk committed
504
            waypointsEditable[i]->setId(i);
505
        }
Alejandro's avatar
Alejandro committed
506

507
        emit waypointEditableListChanged();
508
        emit waypointEditableListChanged(uasid);
509 510 511 512 513
        return 0;
    }
    return -1;
}

514
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
515
{
516
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
517
    {
pixhawk's avatar
pixhawk committed
518
        Waypoint *t = waypointsEditable[cur_seq];
519
        if (cur_seq < new_seq) {
520 521
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
522
                waypointsEditable[i] = waypointsEditable[i+1];
523
                waypointsEditable[i]->setId(i);
524
            }
525 526 527 528 529
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
530
                waypointsEditable[i] = waypointsEditable[i-1];
531
                waypointsEditable[i]->setId(i);
532 533
            }
        }
pixhawk's avatar
pixhawk committed
534
        waypointsEditable[new_seq] = t;
535
        waypointsEditable[new_seq]->setId(new_seq);
536

537
        emit waypointEditableListChanged();
538
        emit waypointEditableListChanged(uasid);
539 540 541
    }
}

542
void UASWaypointManager::saveWaypoints(const QString &saveFile)
543 544 545 546 547 548
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
549 550

    //write the waypoint list version to the first line for compatibility check
551
    out << "QGC WPL 120\r\n";
552

553
    for (int i = 0; i < waypointsEditable.count(); i++)
554
    {
pixhawk's avatar
pixhawk committed
555 556
        waypointsEditable[i]->setId(i);
        waypointsEditable[i]->save(out);
557 558 559 560
    }
    file.close();
}

561
void UASWaypointManager::loadWaypoints(const QString &loadFile)
562 563 564 565 566
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

567
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
568
        Waypoint *t = waypointsEditable[0];
569
        waypointsEditable.removeAt(0);
570 571 572 573
        delete t;
    }

    QTextStream in(&file);
574 575 576

    const QStringList &version = in.readLine().split(" ");

577
    if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120"))
578
    {
579
        emit updateStatusString(tr("The waypoint file is not compatible with the current version of QGroundControl."));
580 581 582 583 584
    }
    else
    {
        while (!in.atEnd())
        {
585
            Waypoint *t = new Waypoint();
586 587
            if(t->load(in))
            {
588 589
                t->setId(waypointsEditable.count());
                waypointsEditable.insert(waypointsEditable.count(), t);
590 591 592
            }
            else
            {
593
                emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
594 595
                break;
            }
596 597
        }
    }
598

599 600
    file.close();

601
    emit loadWPFile();
602
    emit waypointEditableListChanged();
603
    emit waypointEditableListChanged(uasid);
604 605 606
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
607
{
608
    if (current_state == WP_IDLE)
609
    {
610
        emit _startProtocolTimer(); // Start timer on our thread
611
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
612

613 614
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
615
        current_partner_systemid = uasid;
lm's avatar
lm committed
616
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
617

618
        sendWaypointClearAll();
619 620 621
    }
}

622
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
623 624 625 626
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
627
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
628
    foreach (Waypoint* wp, waypointsEditable)
629 630 631
    {
        if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
632 633 634 635 636 637
            wps.append(wp);
        }
    }
    return wps;
}

638
const QList<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
lm's avatar
lm committed
639 640 641 642
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
643
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
644
    foreach (Waypoint* wp, waypointsEditable)
645 646 647
    {
        if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
        {
lm's avatar
lm committed
648 649 650 651 652 653
            wps.append(wp);
        }
    }
    return wps;
}

654
const QList<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
LM's avatar
LM committed
655 656 657 658
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
659
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
660
    foreach (Waypoint* wp, waypointsEditable)
661 662 663
    {
        if (wp->isNavigationType())
        {
LM's avatar
LM committed
664 665 666 667 668 669
            wps.append(wp);
        }
    }
    return wps;
}

670 671
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
672
    return waypointsEditable.indexOf(wp);
673 674
}

675 676
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
677
    // Search through all waypointsEditable,
678 679
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
680
    foreach (Waypoint* p, waypointsEditable) {
681 682 683 684
        if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
            if (p == wp)
            {
685 686 687 688 689 690 691 692 693
                return i;
            }
            i++;
        }
    }

    return -1;
}

lm's avatar
lm committed
694 695
int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
696
    // Search through all waypointsEditable,
lm's avatar
lm committed
697 698
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
699
    foreach (Waypoint* p, waypointsEditable) {
700
        if ((p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
701 702 703
        {
            if (p == wp)
            {
lm's avatar
lm committed
704 705 706 707 708 709 710 711 712
                return i;
            }
            i++;
        }
    }

    return -1;
}

LM's avatar
LM committed
713 714
int UASWaypointManager::getNavTypeIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
715
    // Search through all waypointsEditable,
LM's avatar
LM committed
716 717
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
718
    foreach (Waypoint* p, waypointsEditable)
719 720 721 722 723
    {
        if (p->isNavigationType())
        {
            if (p == wp)
            {
LM's avatar
LM committed
724 725 726 727 728 729 730 731 732
                return i;
            }
            i++;
        }
    }

    return -1;
}

733 734
int UASWaypointManager::getGlobalFrameCount()
{
pixhawk's avatar
pixhawk committed
735
    // Search through all waypointsEditable,
736 737
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
738
    foreach (Waypoint* p, waypointsEditable)
739
    {
740 741
        if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
742 743 744 745 746 747 748
            i++;
        }
    }

    return i;
}

lm's avatar
lm committed
749 750
int UASWaypointManager::getGlobalFrameAndNavTypeCount()
{
pixhawk's avatar
pixhawk committed
751
    // Search through all waypointsEditable,
lm's avatar
lm committed
752 753
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
754
    foreach (Waypoint* p, waypointsEditable) {
755
        if ((p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
756
        {
lm's avatar
lm committed
757 758 759 760 761 762 763
            i++;
        }
    }

    return i;
}

LM's avatar
LM committed
764 765
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
766
    // Search through all waypointsEditable,
LM's avatar
LM committed
767 768
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
769
    foreach (Waypoint* p, waypointsEditable) {
LM's avatar
LM committed
770 771 772 773 774 775 776 777
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

778 779
int UASWaypointManager::getLocalFrameCount()
{
pixhawk's avatar
pixhawk committed
780
    // Search through all waypointsEditable,
781 782
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
783
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
784
    {
785
        if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
lm's avatar
lm committed
786
        {
787 788 789 790 791 792 793 794 795
            i++;
        }
    }

    return i;
}

int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
796
    // Search through all waypointsEditable,
797 798
    // counting only those in local frame
    int i = 0;
pixhawk's avatar
pixhawk committed
799
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
800 801 802
    {
        if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
        {
803 804
            if (p == wp)
            {
805 806 807 808 809 810 811 812 813 814 815
                return i;
            }
            i++;
        }
    }

    return -1;
}

int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
816
    // Search through all waypointsEditable,
817 818
    // counting only those in mission frame
    int i = 0;
pixhawk's avatar
pixhawk committed
819
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
820
    {
821 822 823 824
        if (p->getFrame() == MAV_FRAME_MISSION)
        {
            if (p == wp)
            {
825 826 827 828 829 830 831 832 833
                return i;
            }
            i++;
        }
    }

    return -1;
}

pixhawk's avatar
pixhawk committed
834 835 836 837 838

/**
 * @param readToEdit If true, incoming waypoints will be copied both to "edit"-tab and "view"-tab. Otherwise, only to "view"-tab.
 */
void UASWaypointManager::readWaypoints(bool readToEdit)
839
{
pixhawk's avatar
pixhawk committed
840
    read_to_edit = readToEdit;
841
    emit readGlobalWPFromUAS(true);
842
    if(current_state == WP_IDLE) {
843

844

845 846
        //Clear the old view-list before receiving the new one
        while(waypointsViewOnly.size()>0) {
847
            Waypoint *t = waypointsViewOnly[0];
848
            waypointsViewOnly.removeAt(0);
849
            delete t;
850
        }
851 852
        emit waypointViewOnlyListChanged();
        /* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
853 854
        //Clear the old edit-list before receiving the new one
        if (read_to_edit == true){
855
            while(waypointsEditable.count()>0) {
856 857 858
                Waypoint *t = waypointsEditable[0];
                waypointsEditable.remove(0);
                delete t;
859
            }
860
            emit waypointEditableListChanged();
861
        }
862
        */
863 864 865 866
        
        // We are signalling ourselves here so that the timer gets started on the right thread
        emit _startProtocolTimer();

867
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
868 869 870

        current_state = WP_GETLIST;
        current_wp_id = 0;
871
        current_partner_systemid = uasid;
lm's avatar
lm committed
872
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
873

874
        sendWaypointRequestList();
875

pixhawk's avatar
pixhawk committed
876 877
    }
}
878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911
bool UASWaypointManager::guidedModeSupported()
{
    return (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA);
}

void UASWaypointManager::goToWaypoint(Waypoint *wp)
{
    //Don't try to send a guided mode message to an AP that does not support it.
    if (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
    {
        mavlink_mission_item_t mission;
        memset(&mission, 0, sizeof(mavlink_mission_item_t));   //initialize with zeros
        //const Waypoint *cur_s = waypointsEditable.at(i);

        mission.autocontinue = 0;
        mission.current = 2; //2 for guided mode
        mission.param1 = wp->getParam1();
        mission.param2 = wp->getParam2();
        mission.param3 = wp->getParam3();
        mission.param4 = wp->getParam4();
        mission.frame = wp->getFrame();
        mission.command = wp->getAction();
        mission.seq = 0;     // don't read out the sequence number of the waypoint class
        mission.x = wp->getX();
        mission.y = wp->getY();
        mission.z = wp->getZ();
        mavlink_message_t message;
        mission.target_system = uasid;
        mission.target_component = MAV_COMP_ID_MISSIONPLANNER;
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &mission);
        uas->sendMessage(message);
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
    }
}
pixhawk's avatar
pixhawk committed
912

913
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
914
{
915
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
916
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
917
        if (waypointsEditable.count() > 0) {
918
            emit _startProtocolTimer();  // Start timer on our thread
919
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
920

pixhawk's avatar
pixhawk committed
921
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
922 923
            current_state = WP_SENDLIST;
            current_wp_id = 0;
924
            current_partner_systemid = uasid;
lm's avatar
lm committed
925
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
926 927

            //clear local buffer
pixhawk's avatar
pixhawk committed
928 929 930
            // Why not replace with waypoint_buffer.clear() ?
            // because this will lead to memory leaks, the waypoint-structs
            // have to be deleted, clear() would only delete the pointers.
931
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
932 933 934
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
935

936 937
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
938
            //copy waypoint data to local buffer
939
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
940 941 942
                waypoint_buffer.push_back(new mavlink_mission_item_t);
                mavlink_mission_item_t *cur_d = waypoint_buffer.back();
                memset(cur_d, 0, sizeof(mavlink_mission_item_t));   //initialize with zeros
pixhawk's avatar
pixhawk committed
943
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
944 945

                cur_d->autocontinue = cur_s->getAutoContinue();
946
                cur_d->current = cur_s->getCurrent() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
947 948
                cur_d->param1 = cur_s->getParam1();
                cur_d->param2 = cur_s->getParam2();
lm's avatar
lm committed
949 950
                cur_d->param3 = cur_s->getParam3();
                cur_d->param4 = cur_s->getParam4();
951
                cur_d->frame = cur_s->getFrame();
lm's avatar
lm committed
952
                cur_d->command = cur_s->getAction();
953
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
pixhawk's avatar
pixhawk committed
954 955 956
                cur_d->x = cur_s->getX();
                cur_d->y = cur_s->getY();
                cur_d->z = cur_s->getZ();
957 958 959

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
960 961
                if (i == (current_count - 1) && noCurrent == true) //not a single waypoint was set as "current"
                    cur_d->current = true; // set the last waypoint as current. Or should it better be the first waypoint ?
pixhawk's avatar
pixhawk committed
962
            }
963

964 965 966



pixhawk's avatar
pixhawk committed
967
            //send the waypoint count to UAS (this starts the send transaction)
968
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
969
        } else if (waypointsEditable.count() == 0)
970
        {
971
            clearWaypointList();
972
        }
Lorenz Meier's avatar
Lorenz Meier committed
973 974 975
    }
    else
    {
976 977
        // We're in another transaction, ignore command
        qDebug() << tr("UASWaypointManager::sendWaypoints() doing something else. Ignoring command");
978
    }
pixhawk's avatar
pixhawk committed
979 980
}

981 982
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
983
    if (!uas) return;
984

985 986 987
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
988
    mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
989
    uas->sendMessage(message);
990 991 992 993

    // And update the UI.
    emit updateStatusString(tr("Clearing waypoint list..."));

lm's avatar
lm committed
994
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
995 996 997 998
}

void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
{
lm's avatar
lm committed
999
    if (!uas) return;
1000

1001 1002 1003
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_set_current_t wpsc = {seq, (quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
1004
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
1005
    uas->sendMessage(message);
1006 1007 1008 1009

    // And update the UI.
    emit updateStatusString(tr("Updating target waypoint..."));

lm's avatar
lm committed
1010
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1011 1012 1013 1014
}

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
1015
    if (!uas) return;
1016 1017


1018 1019 1020
    // Tell the UAS how many missions we'll sending.
    mavlink_message_t message;
    mavlink_mission_count_t wpc = {current_count, (quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
1021
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1022
    uas->sendMessage(message);
1023 1024 1025 1026

    // And update the UI.
    emit updateStatusString(tr("Starting to transmit waypoints..."));

lm's avatar
lm committed
1027
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1028 1029 1030 1031
}

void UASWaypointManager::sendWaypointRequestList()
{
lm's avatar
lm committed
1032
    if (!uas) return;
1033

1034 1035 1036 1037 1038
    // Send a MISSION_REQUEST message to the uas for this mission manager, using the MISSIONPLANNER component.
    mavlink_message_t message;
    mavlink_mission_request_list_t wprl = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
    mavlink_msg_mission_request_list_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wprl);
    uas->sendMessage(message);
1039

1040
    // And update the UI.
1041 1042 1043
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1044

lm's avatar
lm committed
1045
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1046 1047
}

1048
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1049
{
lm's avatar
lm committed
1050
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1051

1052 1053 1054
    // Send a MISSION_REQUEST message to the UAS's MISSIONPLANNER component.
    mavlink_message_t message;
    mavlink_mission_request_t wpr = {seq, (quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
1055
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1056
    uas->sendMessage(message);
1057 1058 1059 1060

    // And update the UI.
    emit updateStatusString(tr("Retrieving waypoint ID %1 of %2").arg(wpr.seq).arg(current_count));

lm's avatar
lm committed
1061
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1062
}
pixhawk's avatar
pixhawk committed
1063

pixhawk's avatar
pixhawk committed
1064 1065
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1066
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1067
    mavlink_message_t message;
1068

1069
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1070

1071 1072
        // Fetch the current mission to send, and set it to apply to the curent UAS.
        mavlink_mission_item_t *wp = waypoint_buffer.at(seq);
1073
        wp->target_system = uasid;
lm's avatar
lm committed
1074
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1075

1076
        // Transmit the new mission
lm's avatar
lm committed
1077
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);