UASWaypointManager.cc 38.2 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 590 591 592
              //Use the existing function to add waypoints to the map instead of doing it manually
              //Indeed, we should connect our waypoints to the map in order to synchronize them
              //t->setId(waypointsEditable.count());
              // waypointsEditable.insert(waypointsEditable.count(), t);
              addWaypointEditable(t, false);
593 594 595
            }
            else
            {
596
                emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
597 598
                break;
            }
599 600
        }
    }
601

602 603
    file.close();

604
    emit loadWPFile();
605
    emit waypointEditableListChanged();
606
    emit waypointEditableListChanged(uasid);
607 608 609
}

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

616 617
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
618
        current_partner_systemid = uasid;
lm's avatar
lm committed
619
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
620

621
        sendWaypointClearAll();
622 623 624
    }
}

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

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

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

673 674
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
675
    return waypointsEditable.indexOf(wp);
676 677
}

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

    return -1;
}

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

    return -1;
}

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

    return -1;
}

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

    return i;
}

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

    return i;
}

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

    return i;
}

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

    return i;
}

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

    return -1;
}

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

    return -1;
}

pixhawk's avatar
pixhawk committed
837 838 839 840 841

/**
 * @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)
842
{
pixhawk's avatar
pixhawk committed
843
    read_to_edit = readToEdit;
844
    emit readGlobalWPFromUAS(true);
845
    if(current_state == WP_IDLE) {
846

847

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

870
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
871 872 873

        current_state = WP_GETLIST;
        current_wp_id = 0;
874
        current_partner_systemid = uasid;
lm's avatar
lm committed
875
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
876

877
        sendWaypointRequestList();
878

pixhawk's avatar
pixhawk committed
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 912 913 914
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
915

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

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

            //clear local buffer
pixhawk's avatar
pixhawk committed
931 932 933
            // 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.
934
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
935 936 937
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
938

939 940
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
941
            //copy waypoint data to local buffer
942
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
943 944 945
                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
946
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
947 948

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

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
963 964
                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
965
            }
966

967 968 969



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

984 985
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
986
    if (!uas) return;
987

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

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

lm's avatar
lm committed
997
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
998 999 1000 1001
}

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

1004 1005 1006
    // 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
1007
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
1008
    uas->sendMessage(message);
1009 1010 1011 1012

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

lm's avatar
lm committed
1013
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1014 1015 1016 1017
}

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
1018
    if (!uas) return;
1019 1020


1021 1022 1023
    // 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
1024
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1025
    uas->sendMessage(message);
1026 1027 1028 1029

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

lm's avatar
lm committed
1030
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1031 1032 1033 1034
}

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

1037 1038 1039 1040 1041
    // 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);
1042

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

lm's avatar
lm committed
1048
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1049 1050
}

1051
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1052
{
lm's avatar
lm committed
1053
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1054

1055 1056 1057
    // 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
1058
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1059
    uas->sendMessage(message);
1060 1061 1062 1063

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

lm's avatar
lm committed
1064
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1065
}
pixhawk's avatar
pixhawk committed
1066

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

1072
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1073

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

1079
        // Transmit the new mission
lm's avatar
lm committed
1080
        mavlink_msg_mission_item_encode(uas->mavlink->get