UASWaypointManager.cc 37.7 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 "MainWindow.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 51
      currentWaypointEditable(NULL),
      protocol_timer(this)
pixhawk's avatar
pixhawk committed
52
{
53 54 55 56
    
    _offlineEditingModeTitle = tr("OFFLINE Waypoint Editing Mode");
    _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.");
    
57 58
    if (uas)
    {
lm's avatar
lm committed
59 60 61
        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)));
62
        connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,quint64)));
lm's avatar
lm committed
63 64 65 66
    }
    else
    {
        uasid = 0;
67
    }
68 69 70 71
    
    // 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
72 73
}

LM's avatar
LM committed
74 75 76 77 78
UASWaypointManager::~UASWaypointManager()
{

}

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

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

102
        emit updateStatusString("Operation timed out.");
pixhawk's avatar
pixhawk committed
103

104 105 106 107 108 109
        current_state = WP_IDLE;
        current_count = 0;
        current_wp_id = 0;
        current_partner_systemid = 0;
        current_partner_compid = 0;
    }
110 111
}

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

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

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

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

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


175
    } else {
176
        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);
177
    }
178 179
}

lm's avatar
lm committed
180
void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp)
pixhawk's avatar
pixhawk committed
181
{
182
    if (systemId == current_partner_systemid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id) {
183
        emit _startProtocolTimer(); // Start timer on our thread
184 185
        current_retries = PROTOCOL_MAX_RETRIES;

186
        if(wp->seq == current_wp_id) {
pixhawk's avatar
pixhawk committed
187 188 189 190 191 192 193 194 195 196 197

            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
198 199 200 201

            //get next waypoint
            current_wp_id++;

202
            if(current_wp_id < current_count) {
203
                sendWaypointRequest(current_wp_id);
204
            } else {
205 206
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
207
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
208 209 210 211 212
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
                current_partner_systemid = 0;
                current_partner_compid = 0;
213

214
                emit _stopProtocolTimer(); // Stop timer on our thread
215
                emit readGlobalWPFromUAS(false);
216
                QTime time = QTime::currentTime();
217
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
218

pixhawk's avatar
pixhawk committed
219
            }
220
        } else {
221
            emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
222
        }
223
    } else {
224
        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);
225
    }
pixhawk's avatar
pixhawk committed
226 227
}

lm's avatar
lm committed
228
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
229
{
230 231 232 233 234 235 236 237 238 239
    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) {
240
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
241
            //all waypoints sent and ack received
242
            emit _stopProtocolTimer();  // Stop timer on our thread
243
            current_state = WP_IDLE;
244 245 246
            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()));
247 248
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
249 250 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
            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;
280
            }
281
            emit _stopProtocolTimer();  // Stop timer on our thread
282
            current_state = WP_IDLE;
283
        } else if(current_state == WP_CLEARLIST) {
284
            emit _stopProtocolTimer(); // Stop timer on our thread
285
            current_state = WP_IDLE;
286 287
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
288
        }
289 290 291
    }
}

lm's avatar
lm committed
292
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
293
{
294
    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)))) {
295
        emit _startProtocolTimer();  // Start timer on our thread
296
        current_retries = PROTOCOL_MAX_RETRIES;
297

298
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
299 300 301
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
302
        } else {
pixhawk's avatar
pixhawk committed
303 304
            //TODO: Error message or something
        }
305
    } else {
306
        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);
307
    }
308 309
}

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

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

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

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

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


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

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

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

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

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

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
408 409 410 411

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

        emit waypointViewOnlyListChanged();
417
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
418 419 420 421
    }
}


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

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

444
        emit waypointEditableListChanged();
445
        emit waypointEditableListChanged(uasid);
446
    }
pixhawk's avatar
pixhawk committed
447 448
}

449 450 451 452 453
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
454 455
    // Check if this is the first waypoint in an offline list
    if (waypointsEditable.count() == 0 && uas == NULL)
456
        MainWindow::instance()->showCriticalMessage(_offlineEditingModeTitle, _offlineEditingModeMessage);
457

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

471
    emit waypointEditableListChanged();
472
    emit waypointEditableListChanged(uasid);
473 474 475
    return wp;
}

476
int UASWaypointManager::removeWaypoint(quint16 seq)
477
{
478
    if (seq < waypointsEditable.count())
479
    {
pixhawk's avatar
pixhawk committed
480
        Waypoint *t = waypointsEditable[seq];
481 482 483

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

494
        waypointsEditable.removeAt(seq);
495
        delete t;
496
        t = NULL;
497

498
        for(int i = seq; i < waypointsEditable.count(); i++)
499
        {
pixhawk's avatar
pixhawk committed
500
            waypointsEditable[i]->setId(i);
501
        }
Alejandro's avatar
Alejandro committed
502

503
        emit waypointEditableListChanged();
504
        emit waypointEditableListChanged(uasid);
505 506 507 508 509
        return 0;
    }
    return -1;
}

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

533
        emit waypointEditableListChanged();
534
        emit waypointEditableListChanged(uasid);
535 536 537
    }
}

538
void UASWaypointManager::saveWaypoints(const QString &saveFile)
539 540 541 542 543 544
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
545 546

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

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

557
void UASWaypointManager::loadWaypoints(const QString &loadFile)
558 559 560 561 562
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

563
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
564
        Waypoint *t = waypointsEditable[0];
565
        waypointsEditable.removeAt(0);
566 567 568 569
        delete t;
    }

    QTextStream in(&file);
570 571 572

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

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

595 596
    file.close();

597
    emit loadWPFile();
598
    emit waypointEditableListChanged();
599
    emit waypointEditableListChanged(uasid);
600 601 602
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
603
{
604
    if (current_state == WP_IDLE)
605
    {
606
        emit _startProtocolTimer(); // Start timer on our thread
607
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
608

609 610
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
611
        current_partner_systemid = uasid;
lm's avatar
lm committed
612
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
613

614
        sendWaypointClearAll();
615 616 617
    }
}

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

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

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

666 667
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
668
    return waypointsEditable.indexOf(wp);
669 670
}

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

    return -1;
}

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

    return -1;
}

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

    return -1;
}

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

    return i;
}

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

    return i;
}

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

    return i;
}

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

    return i;
}

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

    return -1;
}

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

    return -1;
}

pixhawk's avatar
pixhawk committed
830 831 832 833 834

/**
 * @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)
835
{
pixhawk's avatar
pixhawk committed
836
    read_to_edit = readToEdit;
837
    emit readGlobalWPFromUAS(true);
838
    if(current_state == WP_IDLE) {
839

840

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

863
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
864 865 866

        current_state = WP_GETLIST;
        current_wp_id = 0;
867
        current_partner_systemid = uasid;
lm's avatar
lm committed
868
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
869

870
        sendWaypointRequestList();
871

pixhawk's avatar
pixhawk committed
872 873
    }
}
874 875 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
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
908

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

pixhawk's avatar
pixhawk committed
917
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
918 919
            current_state = WP_SENDLIST;
            current_wp_id = 0;
920
            current_partner_systemid = uasid;
lm's avatar
lm committed
921
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
922 923

            //clear local buffer
pixhawk's avatar
pixhawk committed
924 925 926
            // 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.
927
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
928 929 930
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
931

932 933
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
934
            //copy waypoint data to local buffer
935
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
936 937 938
                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
939
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
940 941

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

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
956 957
                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
958
            }
959

960 961 962



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

977 978
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
979
    if (!uas) return;
980

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

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

lm's avatar
lm committed
990
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
991 992 993 994
}

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

997 998 999
    // 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
1000
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
1001
    uas->sendMessage(message);
1002 1003 1004 1005

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

lm's avatar
lm committed
1006
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1007 1008 1009 1010
}

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
1011
    if (!uas) return;
1012 1013


1014 1015 1016
    // 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
1017
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1018
    uas->sendMessage(message);
1019 1020 1021 1022

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

lm's avatar
lm committed
1023
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1024 1025 1026 1027
}

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

1030 1031 1032 1033 1034
    // 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);
1035

1036
    // And update the UI.
1037 1038 1039
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1040

lm's avatar
lm committed
1041
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1042 1043
}

1044
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1045
{
lm's avatar
lm committed
1046
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1047

1048 1049 1050
    // 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
1051
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1052
    uas->sendMessage(message);
1053 1054 1055 1056

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

lm's avatar
lm committed
1057
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1058
}
pixhawk's avatar
pixhawk committed
1059

pixhawk's avatar
pixhawk committed
1060 1061
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1062
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1063
    mavlink_message_t message;
1064

1065
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1066

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

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

        // And update the UI.
        emit updateStatusString(tr("Sending waypoint ID %1 of %2 total").arg(wp->seq).arg(current_count));

lm's avatar
lm committed
1079
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1080
    }
pixhawk's avatar
pixhawk committed
1081
}
1082 1083 1084

void UASWaypointManager::sendWaypointAck(quint8 type)
{
lm's avatar
lm committed
1085
    if (!uas) return;
1086

1087 1088 1089
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
lm's avatar
lm committed
1090
    mavlink_msg_mission_ack_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpa);
1091
    uas->sendMessage(message);
1092

lm's avatar
lm committed
1093
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1094
}
1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119

UAS* UASWaypointManager::getUAS() {
    return this->uas;    ///< Returns the owning UAS
}

float UASWaypointManager::getAltitudeRecommendation()
{
    if (waypointsEditable.count() > 0) {
        return waypointsEditable.last()->getAltitude();
    } else {
        return UASManager::instance()->getHomeAltitude() + getHomeAltitudeOffsetDefault();
    }
}

int UASWaypointManager::getFrameRecommendation()
{
    if (waypointsEditable.count() > 0) {
        return static_cast<int>(waypointsEditable.last()->getFrame());
    } else {
        return MAV_FRAME_GLOBAL;
    }
}

float UASWaypointManager::getAcceptanceRadiusRecommendation()
{
1120 1121
    if (waypointsEditable.count() > 0)
    {
1122 1123
        return waypointsEditable.last()->getAcceptanceRadius();
    }
1124 1125
    else
    {
1126 1127
        // Default to rotary wing waypoint radius for offline editing
        if (!uas || uas->isRotaryWing())
1128
        {
Thomas Gubler's avatar
Thomas Gubler committed
1129 1130 1131 1132 1133 1134
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
        else if (uas->isFixedWing())
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1135 1136 1137
    }

    return 10.0f;
1138 1139 1140 1141 1142 1143
}

float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
    return defaultAltitudeHomeOffset;
}
1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154


void UASWaypointManager::_startProtocolTimerOnThisThread(void)
{
    protocol_timer.start(PROTOCOL_TIMEOUT_MS);
}

void UASWaypointManager::_stopProtocolTimerOnThisThread(void)
{
    protocol_timer.stop();
}