UASWaypointManager.cc 38.8 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

Gus Grubba's avatar
Gus Grubba committed
182 183 184 185 186 187 188 189 190 191 192 193 194
            Waypoint *lwp_vo = new Waypoint(
                NULL,
                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);
pixhawk's avatar
pixhawk committed
195

Gus Grubba's avatar
Gus Grubba committed
196
            addWaypointViewOnly(lwp_vo);
pixhawk's avatar
pixhawk committed
197 198

            if (read_to_edit == true) {
Gus Grubba's avatar
Gus Grubba committed
199 200 201 202 203 204 205 206 207 208 209 210 211 212
                Waypoint *lwp_ed = new Waypoint(
                    NULL,
                    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);
pixhawk's avatar
pixhawk committed
213 214 215 216
                addWaypointEditable(lwp_ed, false);
                if (wp->current == 1) currentWaypointEditable = lwp_ed;
            }

pixhawk's avatar
pixhawk committed
217 218 219 220

            //get next waypoint
            current_wp_id++;

221
            if(current_wp_id < current_count) {
222
                sendWaypointRequest(current_wp_id);
223
            } else {
224 225
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
226
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
227 228 229
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
230

231
                emit _stopProtocolTimer(); // Stop timer on our thread
232
                emit readGlobalWPFromUAS(false);
233
                QTime time = QTime::currentTime();
234
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
235

pixhawk's avatar
pixhawk committed
236
            }
237
        } else {
238
            emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
239
        }
240 241 242 243
    } 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
Gus Grubba's avatar
Gus Grubba committed
244 245 246 247 248 249 250 251 252 253 254 255 256 257
        Waypoint *lwp_vo = new Waypoint(
            NULL,
            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);
258 259 260 261 262

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

263
    } else {
264
        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);
265
    }
pixhawk's avatar
pixhawk committed
266 267
}

lm's avatar
lm committed
268
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
269
{
270 271 272 273 274 275 276 277 278 279
    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) {
280
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
281
            //all waypoints sent and ack received
282
            emit _stopProtocolTimer();  // Stop timer on our thread
283
            current_state = WP_IDLE;
284 285 286
            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()));
287 288
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319
            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;
320
            }
321
            emit _stopProtocolTimer();  // Stop timer on our thread
322
            current_state = WP_IDLE;
323
        } else if(current_state == WP_CLEARLIST) {
324
            emit _stopProtocolTimer(); // Stop timer on our thread
325
            current_state = WP_IDLE;
326 327
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
328
        }
329 330 331
    }
}

lm's avatar
lm committed
332
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
333
{
334
    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)))) {
335
        emit _startProtocolTimer();  // Start timer on our thread
336
        current_retries = PROTOCOL_MAX_RETRIES;
337

338
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
339 340 341
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
342
        } else {
pixhawk's avatar
pixhawk committed
343 344
            //TODO: Error message or something
        }
345
    } else {
346
        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);
347
    }
348 349
}

lm's avatar
lm committed
350
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
351
{
352
	Q_UNUSED(compId);
lm's avatar
lm committed
353
    if (!uas) return;
354
    if (systemId == uasid) {
355
        emit updateStatusString(tr("Reached waypoint %1").arg(wpr->seq));
pixhawk's avatar
pixhawk committed
356
    }
pixhawk's avatar
pixhawk committed
357 358
}

lm's avatar
lm committed
359
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
360
{
361
    Q_UNUSED(compId);
lm's avatar
lm committed
362
    if (!uas) return;
363
    if (systemId == uasid) {
364
        // FIXME Petri
365
        if (current_state == WP_SETCURRENT) {
366
            emit _stopProtocolTimer();  // Stop timer on our thread
367
            current_state = WP_IDLE;
368 369

            // update the local main storage
pixhawk's avatar
pixhawk committed
370 371 372 373
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
                    if (waypointsViewOnly[i]->getId() == wpc->seq) {
                        waypointsViewOnly[i]->setCurrent(true);
374
                    } else {
pixhawk's avatar
pixhawk committed
375
                        waypointsViewOnly[i]->setCurrent(false);
376 377 378
                    }
                }
            }
379
        }
380
        emit updateStatusString(tr("New current waypoint %1").arg(wpc->seq));
381 382
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
383
    }
pixhawk's avatar
pixhawk committed
384 385
}

386
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
387
{
388
    // If only one waypoint was changed, emit only WP signal
389
    if (wp != NULL) {
390
        emit waypointEditableChanged(uasid, wp);
391
    } else {
392
        emit waypointEditableListChanged();
393
        emit waypointEditableListChanged(uasid);
394
    }
395 396
}

397 398 399
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
400
        emit waypointViewOnlyChanged(uasid, wp);
401 402
    } else {
        emit waypointViewOnlyListChanged();
403
        emit waypointViewOnlyListChanged(uasid);
404 405
    }
}
406 407


408
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
409
{
pixhawk's avatar
pixhawk committed
410
    if (seq < waypointsViewOnly.size()) {
411
        if(current_state == WP_IDLE) {
412

413
            //send change to UAS - important to note: if the transmission fails, we have inconsistencies
414
            emit _startProtocolTimer();  // Start timer on our thread
415 416 417 418
            current_retries = PROTOCOL_MAX_RETRIES;

            current_state = WP_SETCURRENT;
            current_wp_id = seq;
419
            current_partner_systemid = uasid;
lm's avatar
lm committed
420
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
421 422 423 424 425 426 427 428 429

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

430 431
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
432
    if (seq < waypointsEditable.count()) {
433 434
        if(current_state == WP_IDLE) {
            //update local main storage
435
            for (int i = 0; i < waypointsEditable.count(); i++) {
436 437 438 439 440 441 442 443 444 445 446 447
                if (waypointsEditable[i]->getId() == seq) {
                    waypointsEditable[i]->setCurrent(true);
                } else {
                    waypointsEditable[i]->setCurrent(false);
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
448 449 450 451

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
452
    {
pixhawk's avatar
pixhawk committed
453 454 455 456
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
457
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
458 459 460 461
    }
}


pixhawk's avatar
pixhawk committed
462
/**
463
 * @warning Make sure the waypoint stays valid for the whole application lifecycle!
pixhawk's avatar
pixhawk committed
464
 * @param enforceFirstActive Enforces that the first waypoint is set as active
465
 * @see createWaypoint() is more suitable for most use cases
pixhawk's avatar
pixhawk committed
466
 */
467
void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive)
468
{
lm's avatar
lm committed
469 470
    if (wp)
    {
471
        // Check if this is the first waypoint in an offline list
472 473 474
        if (waypointsEditable.count() == 0 && uas == NULL) {
            QGCMessageBox::critical(tr("Waypoint Manager"),  _offlineEditingModeMessage);
        }
475

476 477
        wp->setId(waypointsEditable.count());
        if (enforceFirstActive && waypointsEditable.count() == 0)
478 479
        {
            wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
480
            currentWaypointEditable = wp;
481
        }
482
        waypointsEditable.insert(waypointsEditable.count(), wp);
483
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
484

485
        emit waypointEditableListChanged();
486
        emit waypointEditableListChanged(uasid);
487
    }
pixhawk's avatar
pixhawk committed
488 489
}

490 491 492 493 494
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
495
    // Check if this is the first waypoint in an offline list
496 497 498
    if (waypointsEditable.count() == 0 && uas == NULL) {
        QGCMessageBox::critical(tr("Waypoint Manager"),  _offlineEditingModeMessage);
    }
499

500
    Waypoint* wp = new Waypoint();
501 502 503
    wp->setId(waypointsEditable.count());
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
504
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
505
    if (enforceFirstActive && waypointsEditable.count() == 0)
506 507
    {
        wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
508
        currentWaypointEditable = wp;
509
    }
510
    waypointsEditable.append(wp);
511
    connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
512

513
    emit waypointEditableListChanged();
514
    emit waypointEditableListChanged(uasid);
515 516 517
    return wp;
}

518
int UASWaypointManager::removeWaypoint(quint16 seq)
519
{
520
    if (seq < waypointsEditable.count())
521
    {
pixhawk's avatar
pixhawk committed
522
        Waypoint *t = waypointsEditable[seq];
523 524 525

        if (t->getCurrent() == true) //trying to remove the current waypoint
        {
526
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
527 528 529
            {
                waypointsEditable[seq+1]->setCurrent(true);
            }
530
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
531 532 533 534 535
            {
                waypointsEditable[seq-1]->setCurrent(true);
            }
        }

536
        waypointsEditable.removeAt(seq);
537
        delete t;
538
        t = NULL;
539

540
        for(int i = seq; i < waypointsEditable.count(); i++)
541
        {
pixhawk's avatar
pixhawk committed
542
            waypointsEditable[i]->setId(i);
543
        }
Alejandro's avatar
Alejandro committed
544

545
        emit waypointEditableListChanged();
546
        emit waypointEditableListChanged(uasid);
547 548 549 550 551
        return 0;
    }
    return -1;
}

552
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
553
{
554
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
555
    {
pixhawk's avatar
pixhawk committed
556
        Waypoint *t = waypointsEditable[cur_seq];
557
        if (cur_seq < new_seq) {
558 559
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
560
                waypointsEditable[i] = waypointsEditable[i+1];
561
                waypointsEditable[i]->setId(i);
562
            }
563 564 565 566 567
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
568
                waypointsEditable[i] = waypointsEditable[i-1];
569
                waypointsEditable[i]->setId(i);
570 571
            }
        }
pixhawk's avatar
pixhawk committed
572
        waypointsEditable[new_seq] = t;
573
        waypointsEditable[new_seq]->setId(new_seq);
574

575
        emit waypointEditableListChanged();
576
        emit waypointEditableListChanged(uasid);
577 578 579
    }
}

580
void UASWaypointManager::saveWaypoints(const QString &saveFile)
581 582 583 584 585 586
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
587 588

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

591
    for (int i = 0; i < waypointsEditable.count(); i++)
592
    {
pixhawk's avatar
pixhawk committed
593 594
        waypointsEditable[i]->setId(i);
        waypointsEditable[i]->save(out);
595 596 597 598
    }
    file.close();
}

599
void UASWaypointManager::loadWaypoints(const QString &loadFile)
600 601 602 603 604
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

605
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
606
        Waypoint *t = waypointsEditable[0];
607
        waypointsEditable.removeAt(0);
608 609 610 611
        delete t;
    }

    QTextStream in(&file);
612 613 614

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

615
    if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120"))
616
    {
617
        emit updateStatusString(tr("The waypoint file is not compatible with the current version of QGroundControl."));
618 619 620 621 622
    }
    else
    {
        while (!in.atEnd())
        {
623
            Waypoint *t = new Waypoint();
624 625
            if(t->load(in))
            {
626 627 628 629 630
              //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);
631 632 633
            }
            else
            {
634
                emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
635 636
                break;
            }
637 638
        }
    }
639

640 641
    file.close();

642
    emit loadWPFile();
643
    emit waypointEditableListChanged();
644
    emit waypointEditableListChanged(uasid);
645 646 647
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
648
{
649
    if (current_state == WP_IDLE)
650
    {
651
        emit _startProtocolTimer(); // Start timer on our thread
652
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
653

654 655
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
656
        current_partner_systemid = uasid;
lm's avatar
lm committed
657
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
658

659
        sendWaypointClearAll();
660 661 662
    }
}

663
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
664 665 666 667
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
668
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
669
    foreach (Waypoint* wp, waypointsEditable)
670 671 672
    {
        if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
673 674 675 676 677 678
            wps.append(wp);
        }
    }
    return wps;
}

679
const QList<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
lm's avatar
lm committed
680 681 682 683
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
684
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
685
    foreach (Waypoint* wp, waypointsEditable)
686 687 688
    {
        if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
        {
lm's avatar
lm committed
689 690 691 692 693 694
            wps.append(wp);
        }
    }
    return wps;
}

695
const QList<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
LM's avatar
LM committed
696 697 698 699
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
700
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
701
    foreach (Waypoint* wp, waypointsEditable)
702 703 704
    {
        if (wp->isNavigationType())
        {
LM's avatar
LM committed
705 706 707 708 709 710
            wps.append(wp);
        }
    }
    return wps;
}

711 712
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
713
    return waypointsEditable.indexOf(wp);
714 715
}

716 717
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
718
    // Search through all waypointsEditable,
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
        if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
            if (p == wp)
            {
726 727 728 729 730 731 732 733 734
                return i;
            }
            i++;
        }
    }

    return -1;
}

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

    return -1;
}

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

    return -1;
}

774 775
int UASWaypointManager::getGlobalFrameCount()
{
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)
780
    {
781 782
        if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
783 784 785 786 787 788 789
            i++;
        }
    }

    return i;
}

lm's avatar
lm committed
790 791
int UASWaypointManager::getGlobalFrameAndNavTypeCount()
{
pixhawk's avatar
pixhawk committed
792
    // Search through all waypointsEditable,
lm's avatar
lm committed
793 794
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
795
    foreach (Waypoint* p, waypointsEditable) {
796
        if ((p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
797
        {
lm's avatar
lm committed
798 799 800 801 802 803 804
            i++;
        }
    }

    return i;
}

LM's avatar
LM committed
805 806
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
807
    // Search through all waypointsEditable,
LM's avatar
LM committed
808 809
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
810
    foreach (Waypoint* p, waypointsEditable) {
LM's avatar
LM committed
811 812 813 814 815 816 817 818
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

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

    return i;
}

int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
837
    // Search through all waypointsEditable,
838 839
    // counting only those in local frame
    int i = 0;
pixhawk's avatar
pixhawk committed
840
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
841 842 843
    {
        if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
        {
844 845
            if (p == wp)
            {
846 847 848 849 850 851 852 853 854 855 856
                return i;
            }
            i++;
        }
    }

    return -1;
}

int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
857
    // Search through all waypointsEditable,
858 859
    // counting only those in mission frame
    int i = 0;
pixhawk's avatar
pixhawk committed
860
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
861
    {
862 863 864 865
        if (p->getFrame() == MAV_FRAME_MISSION)
        {
            if (p == wp)
            {
866 867 868 869 870 871 872 873 874
                return i;
            }
            i++;
        }
    }

    return -1;
}

pixhawk's avatar
pixhawk committed
875 876 877 878 879

/**
 * @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)
880
{
pixhawk's avatar
pixhawk committed
881
    read_to_edit = readToEdit;
882
    emit readGlobalWPFromUAS(true);
883
    if(current_state == WP_IDLE) {
884

885

886 887
        //Clear the old view-list before receiving the new one
        while(waypointsViewOnly.size()>0) {
888
            Waypoint *t = waypointsViewOnly[0];
889
            waypointsViewOnly.removeAt(0);
890
            delete t;
891
        }
892 893
        emit waypointViewOnlyListChanged();
        /* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
894 895
        //Clear the old edit-list before receiving the new one
        if (read_to_edit == true){
896
            while(waypointsEditable.count()>0) {
897 898 899
                Waypoint *t = waypointsEditable[0];
                waypointsEditable.remove(0);
                delete t;
900
            }
901
            emit waypointEditableListChanged();
902
        }
903
        */
904 905 906 907
        
        // We are signalling ourselves here so that the timer gets started on the right thread
        emit _startProtocolTimer();

908
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
909 910 911

        current_state = WP_GETLIST;
        current_wp_id = 0;
912
        current_partner_systemid = uasid;
lm's avatar
lm committed
913
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
914

915
        sendWaypointRequestList();
916

pixhawk's avatar
pixhawk committed
917 918
    }
}
919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952
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
953

954
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
955
{
956
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
957
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
958
        if (waypointsEditable.count() > 0) {
959
            emit _startProtocolTimer();  // Start timer on our thread
960
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
961

pixhawk's avatar
pixhawk committed
962
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
963 964
            current_state = WP_SENDLIST;
            current_wp_id = 0;
965
            current_partner_systemid = uasid;
lm's avatar
lm committed
966
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
967 968

            //clear local buffer
pixhawk's avatar
pixhawk committed
969 970 971
            // 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.
972
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
973 974 975
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
976

977 978
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
979
            //copy waypoint data to local buffer
980
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
981 982 983
                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
984
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
985 986

                cur_d->autocontinue = cur_s->getAutoContinue();
987
                cur_d->current = cur_s->getCurrent() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
988 989
                cur_d->param1 = cur_s->getParam1();
                cur_d->param2 = cur_s->getParam2();
lm's avatar
lm committed
990 991
                cur_d->param3 = cur_s->getParam3();
                cur_d->param4 = cur_s->getParam4();
992
                cur_d->frame = cur_s->getFrame();
lm's avatar
lm committed
993
                cur_d->command = cur_s->getAction();
994
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
pixhawk's avatar
pixhawk committed
995 996 997
                cur_d->x = cur_s->getX();
                cur_d->y = cur_s->getY();
                cur_d->z = cur_s->getZ();
998 999 1000

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
1001 1002
                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
1003
            }
1004

1005 1006 1007



pixhawk's avatar
pixhawk committed
1008
            //send the waypoint count to UAS (this starts the send transaction)
1009
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
1010
        } else if (waypointsEditable.count() == 0)
1011
        {
1012
            clearWaypointList();
1013
        }
Lorenz Meier's avatar
Lorenz Meier committed
1014 1015 1016
    }
    else
    {
1017 1018
        // We're in another transaction, ignore command
        qDebug() << tr("UASWaypointManager::sendWaypoints() doing something else. Ignoring command");
1019
    }
pixhawk's avatar
pixhawk committed
1020 1021
}

1022 1023
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
1024
    if (!uas) return;
1025

1026 1027 1028
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
1029
    mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
1030
    uas->sendMessage(message);
1031 1032 1033 1034

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

lm's avatar
lm committed
1035
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1036 1037 1038 1039
}

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

1042 1043 1044
    // 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
1045
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
1046
    uas->sendMessage(message);
1047 1048 1049 1050

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

lm's avatar
lm committed
1051
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1052 1053 1054 1055
}

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
1056
    if (!uas) return;
1057 1058


1059 1060 1061
    // 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
1062
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1063
    uas->sendMessage(message);
1064 1065 1066 1067

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

lm's avatar
lm committed
1068
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1069 1070 1071 1072
}

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

1075 1076 1077 1078 1079
    // 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);
1080

1081
    // And update the UI.
1082 1083 1084
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1085

lm's avatar
lm committed
1086
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1087 1088
}

1089
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1090
{
lm's avatar
lm committed
1091
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1092

1093 1094 1095
    // 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
1096
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1097
    uas->sendMessage(message);
1098 1099 1100 1101

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

lm's avatar
lm committed
1102
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1103
}
pixhawk's avatar
pixhawk committed
1104

pixhawk's avatar
pixhawk committed
1105 1106
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1107
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1108
    mavlink_message_t message;
1109

1110
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1111

1112 1113
        // Fetch the current mission to send, and set it to apply to the curent UAS.
        mavlink_mission_item_t *wp = waypoint_buffer.at(seq);
1114
        wp->target_system = uasid;
lm's avatar
lm committed
1115
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1116

1117
        // Transmit the new mission
lm's avatar
lm committed
1118
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);
1119
        uas->sendMessage(message);
1120 1121 1122 1123

        // 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
1124
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1125
    }
pixhawk's avatar
pixhawk committed
1126
}
1127 1128 1129

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

1132 1133 1134
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
lm's avatar
lm committed
1135
    mavlink_msg_mission_ack_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpa);
1136
    uas->sendMessage(message);
1137

lm's avatar
lm committed
1138
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1139
}
1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164

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()
{
1165 1166
    if (waypointsEditable.count() > 0)
    {
1167 1168
        return waypointsEditable.last()->getAcceptanceRadius();
    }
1169 1170
    else
    {
1171 1172
        // Default to rotary wing waypoint radius for offline editing
        if (!uas || uas->isRotaryWing())
1173
        {
Thomas Gubler's avatar
Thomas Gubler committed
1174 1175 1176 1177 1178 1179
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
        else if (uas->isFixedWing())
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1180 1181 1182
    }

    return 10.0f;
1183 1184 1185 1186 1187 1188
}

float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
    return defaultAltitudeHomeOffset;
}
1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199


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

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