UASWaypointManager.cc 34.4 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
    if (uas)
    {
lm's avatar
lm committed
55 56 57 58 59 60 61 62
        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)));
        connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
    }
    else
    {
        uasid = 0;
63
    }
pixhawk's avatar
pixhawk committed
64 65
}

LM's avatar
LM committed
66 67 68 69 70
UASWaypointManager::~UASWaypointManager()
{

}

pixhawk's avatar
pixhawk committed
71
void UASWaypointManager::timeout()
72
{
73
    if (current_retries > 0) {
74 75
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries--;
76
        emit updateStatusString(tr("Timeout, retrying (retries left: %1)").arg(current_retries));
77

78
        if (current_state == WP_GETLIST) {
79
            sendWaypointRequestList();
80
        } else if (current_state == WP_GETLIST_GETWPS) {
81
            sendWaypointRequest(current_wp_id);
82
        } else if (current_state == WP_SENDLIST) {
83
            sendWaypointCount();
84
        } else if (current_state == WP_SENDLIST_SENDWPS) {
85
            sendWaypoint(current_wp_id);
86
        } else if (current_state == WP_CLEARLIST) {
87
            sendWaypointClearAll();
88
        } else if (current_state == WP_SETCURRENT) {
89 90
            sendWaypointSetCurrent(current_wp_id);
        }
91
    } else {
92
        protocol_timer.stop();
pixhawk's avatar
pixhawk committed
93

94
        emit updateStatusString("Operation timed out.");
pixhawk's avatar
pixhawk committed
95

96 97 98 99 100 101
        current_state = WP_IDLE;
        current_count = 0;
        current_wp_id = 0;
        current_partner_systemid = 0;
        current_partner_compid = 0;
    }
102 103
}

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

void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time)
{
120 121
    Q_UNUSED(mav);
    Q_UNUSED(time);
122 123 124
	Q_UNUSED(alt);
	Q_UNUSED(lon);
	Q_UNUSED(lat);
125 126 127 128 129 130
    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);
    }
131 132
}

133 134
void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count)
{
135
    if (current_state == WP_GETLIST && systemId == current_partner_systemid) {
136 137 138
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries = PROTOCOL_MAX_RETRIES;

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

149
        if (count > 0) {
pixhawk's avatar
pixhawk committed
150 151 152 153
            current_count = count;
            current_wp_id = 0;
            current_state = WP_GETLIST_GETWPS;
            sendWaypointRequest(current_wp_id);
154
        } else {
155
            protocol_timer.stop();
pixhawk's avatar
pixhawk committed
156
            emit updateStatusString("done.");
157 158 159 160 161
            current_state = WP_IDLE;
            current_count = 0;
            current_wp_id = 0;
            current_partner_systemid = 0;
            current_partner_compid = 0;
pixhawk's avatar
pixhawk committed
162
        }
163 164


165 166
    } else {
        qDebug("Rejecting 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);
167
    }
168 169
}

lm's avatar
lm committed
170
void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp)
pixhawk's avatar
pixhawk committed
171
{
172
    if (systemId == current_partner_systemid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id) {
173 174 175
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries = PROTOCOL_MAX_RETRIES;

176
        if(wp->seq == current_wp_id) {
pixhawk's avatar
pixhawk committed
177 178 179 180 181 182 183 184 185 186 187

            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
188 189 190 191

            //get next waypoint
            current_wp_id++;

192
            if(current_wp_id < current_count) {
193
                sendWaypointRequest(current_wp_id);
194
            } else {
195 196
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
197
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
198 199 200 201 202
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
                current_partner_systemid = 0;
                current_partner_compid = 0;
203

pixhawk's avatar
pixhawk committed
204
                protocol_timer.stop();
205
                emit readGlobalWPFromUAS(false);
206 207 208
                QTime time = QTime::currentTime();
                QString timeString = time.toString();
                emit updateStatusString(tr("done. (updated at %1)").arg(timeString));
209

pixhawk's avatar
pixhawk committed
210
            }
211
        } else {
212
            emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
213
        }
214 215
    } else {
        qDebug("Rejecting 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);
216
    }
pixhawk's avatar
pixhawk committed
217 218
}

lm's avatar
lm committed
219
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
220
{
221
    if (systemId == current_partner_systemid && (compId == current_partner_compid || compId == MAV_COMP_ID_ALL)) {
222
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
223 224
            //all waypoints sent and ack received
            protocol_timer.stop();
225
            current_state = WP_IDLE;
226
            readWaypoints(false); //Update "Onboard Waypoints"-tab immidiately after the waypoint list has been sent.
227
            emit updateStatusString("done.");
228
        } else if(current_state == WP_CLEARLIST) {
229 230 231 232
            protocol_timer.stop();
            current_state = WP_IDLE;
            emit updateStatusString("done.");
        }
233 234 235
    }
}

lm's avatar
lm committed
236
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
237
{
238
    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)))) {
239 240
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries = PROTOCOL_MAX_RETRIES;
241

242
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
243 244 245
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
246
        } else {
pixhawk's avatar
pixhawk committed
247 248
            //TODO: Error message or something
        }
249 250
    } else {
        qDebug("Rejecting 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);
251
    }
252 253
}

lm's avatar
lm committed
254
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
255
{
256
	Q_UNUSED(compId);
lm's avatar
lm committed
257
    if (!uas) return;
258
    if (systemId == uasid) {
pixhawk's avatar
pixhawk committed
259 260
        emit updateStatusString(QString("Reached waypoint %1").arg(wpr->seq));
    }
pixhawk's avatar
pixhawk committed
261 262
}

lm's avatar
lm committed
263
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
264
{
265
    Q_UNUSED(compId);
lm's avatar
lm committed
266
    if (!uas) return;
267
    if (systemId == uasid) {
268
        // FIXME Petri
269
        if (current_state == WP_SETCURRENT) {
270 271
            protocol_timer.stop();
            current_state = WP_IDLE;
272 273

            // update the local main storage
pixhawk's avatar
pixhawk committed
274 275 276 277
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
                    if (waypointsViewOnly[i]->getId() == wpc->seq) {
                        waypointsViewOnly[i]->setCurrent(true);
278
                    } else {
pixhawk's avatar
pixhawk committed
279
                        waypointsViewOnly[i]->setCurrent(false);
280 281 282
                    }
                }
            }
283
        }
284 285 286
        emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
287
    }
pixhawk's avatar
pixhawk committed
288 289
}

290
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
291
{
292
    // If only one waypoint was changed, emit only WP signal
293
    if (wp != NULL) {
294
        emit waypointEditableChanged(uasid, wp);
295
    } else {
296
        emit waypointEditableListChanged();
297
        emit waypointEditableListChanged(uasid);
298
    }
299 300
}

301 302 303
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
304
        emit waypointViewOnlyChanged(uasid, wp);
305 306
    } else {
        emit waypointViewOnlyListChanged();
307
        emit waypointViewOnlyListChanged(uasid);
308 309
    }
}
310 311


312
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
313
{
pixhawk's avatar
pixhawk committed
314
    if (seq < waypointsViewOnly.size()) {
315
        if(current_state == WP_IDLE) {
316

317 318 319 320 321 322
            //send change to UAS - important to note: if the transmission fails, we have inconsistencies
            protocol_timer.start(PROTOCOL_TIMEOUT_MS);
            current_retries = PROTOCOL_MAX_RETRIES;

            current_state = WP_SETCURRENT;
            current_wp_id = seq;
323
            current_partner_systemid = uasid;
lm's avatar
lm committed
324
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
325 326 327 328 329 330 331 332 333

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

334 335
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
336
    if (seq < waypointsEditable.count()) {
337 338
        if(current_state == WP_IDLE) {
            //update local main storage
339
            for(int i = 0; i < waypointsEditable.count(); i++) {
340 341 342 343 344 345 346 347 348 349 350 351
                if (waypointsEditable[i]->getId() == seq) {
                    waypointsEditable[i]->setCurrent(true);
                } else {
                    waypointsEditable[i]->setCurrent(false);
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
352 353 354 355

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
356
    {
pixhawk's avatar
pixhawk committed
357 358 359 360
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
361
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
362 363 364 365
    }
}


pixhawk's avatar
pixhawk committed
366
/**
367
 * @warning Make sure the waypoint stays valid for the whole application lifecycle!
pixhawk's avatar
pixhawk committed
368
 * @param enforceFirstActive Enforces that the first waypoint is set as active
369
 * @see createWaypoint() is more suitable for most use cases
pixhawk's avatar
pixhawk committed
370
 */
371
void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive)
372
{
lm's avatar
lm committed
373 374
    if (wp)
    {
375 376 377 378
        // Check if this is the first waypoint in an offline list
        if (waypointsEditable.count() == 0 && uas == NULL)
            MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe 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."));

379 380
        wp->setId(waypointsEditable.count());
        if (enforceFirstActive && waypointsEditable.count() == 0)
381 382
        {
            wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
383
            currentWaypointEditable = wp;
384
        }
385
        waypointsEditable.insert(waypointsEditable.count(), wp);
386
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
387

388
        emit waypointEditableListChanged();
389
        emit waypointEditableListChanged(uasid);
390
    }
pixhawk's avatar
pixhawk committed
391 392
}

393 394 395 396 397
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
398 399 400 401
    // Check if this is the first waypoint in an offline list
    if (waypointsEditable.count() == 0 && uas == NULL)
        MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe 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."));

402
    Waypoint* wp = new Waypoint();
403 404 405
    wp->setId(waypointsEditable.count());
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
406
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
407
    if (enforceFirstActive && waypointsEditable.count() == 0)
408 409
    {
        wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
410
        currentWaypointEditable = wp;
411
    }
412
    waypointsEditable.append(wp);
413
    connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
414

415
    emit waypointEditableListChanged();
416
    emit waypointEditableListChanged(uasid);
417 418 419
    return wp;
}

420
int UASWaypointManager::removeWaypoint(quint16 seq)
421
{
422
    if (seq < waypointsEditable.count())
423
    {
pixhawk's avatar
pixhawk committed
424
        Waypoint *t = waypointsEditable[seq];
425 426 427

        if (t->getCurrent() == true) //trying to remove the current waypoint
        {
428
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
429 430 431
            {
                waypointsEditable[seq+1]->setCurrent(true);
            }
432
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
433 434 435 436 437
            {
                waypointsEditable[seq-1]->setCurrent(true);
            }
        }

438
        waypointsEditable.removeAt(seq);
439
        delete t;
440
        t = NULL;
441

442
        for(int i = seq; i < waypointsEditable.count(); i++)
443
        {
pixhawk's avatar
pixhawk committed
444
            waypointsEditable[i]->setId(i);
445
        }
Alejandro's avatar
Alejandro committed
446

447
        emit waypointEditableListChanged();
448
        emit waypointEditableListChanged(uasid);
449 450 451 452 453
        return 0;
    }
    return -1;
}

454
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
455
{
456
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
457
    {
pixhawk's avatar
pixhawk committed
458
        Waypoint *t = waypointsEditable[cur_seq];
459
        if (cur_seq < new_seq) {
460 461
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
462
                waypointsEditable[i] = waypointsEditable[i+1];
463
                waypointsEditable[i]->setId(i);
464
            }
465 466 467 468 469
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
470
                waypointsEditable[i] = waypointsEditable[i-1];
471
                waypointsEditable[i]->setId(i);
472 473
            }
        }
pixhawk's avatar
pixhawk committed
474
        waypointsEditable[new_seq] = t;
475
        waypointsEditable[new_seq]->setId(new_seq);
476

477
        emit waypointEditableListChanged();
478
        emit waypointEditableListChanged(uasid);
479 480 481
    }
}

482
void UASWaypointManager::saveWaypoints(const QString &saveFile)
483 484 485 486 487 488
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
489 490

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

493
    for (int i = 0; i < waypointsEditable.count(); i++)
494
    {
pixhawk's avatar
pixhawk committed
495 496
        waypointsEditable[i]->setId(i);
        waypointsEditable[i]->save(out);
497 498 499 500
    }
    file.close();
}

501
void UASWaypointManager::loadWaypoints(const QString &loadFile)
502 503 504 505 506
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

507
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
508
        Waypoint *t = waypointsEditable[0];
509
        waypointsEditable.removeAt(0);
510 511 512 513
        delete t;
    }

    QTextStream in(&file);
514 515 516

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

517
    if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120"))
518
    {
519
        emit updateStatusString(tr("The waypoint file is not compatible with the current version of QGroundControl."));
520 521 522 523 524
    }
    else
    {
        while (!in.atEnd())
        {
525
            Waypoint *t = new Waypoint();
526 527
            if(t->load(in))
            {
528 529
                t->setId(waypointsEditable.count());
                waypointsEditable.insert(waypointsEditable.count(), t);
530 531 532
            }
            else
            {
533
                emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
534 535
                break;
            }
536 537
        }
    }
538

539 540
    file.close();

541
    emit loadWPFile();
542
    emit waypointEditableListChanged();
543
    emit waypointEditableListChanged(uasid);
544 545 546
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
547
{
548
    if (current_state == WP_IDLE)
549
    {
pixhawk's avatar
pixhawk committed
550
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
551
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
552

553 554
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
555
        current_partner_systemid = uasid;
lm's avatar
lm committed
556
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
557

558
        sendWaypointClearAll();
559 560 561
    }
}

562
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
563 564 565 566
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
567
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
568
    foreach (Waypoint* wp, waypointsEditable)
569 570 571
    {
        if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
572 573 574 575 576 577
            wps.append(wp);
        }
    }
    return wps;
}

578
const QList<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
lm's avatar
lm committed
579 580 581 582
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
583
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
584
    foreach (Waypoint* wp, waypointsEditable)
585 586 587
    {
        if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
        {
lm's avatar
lm committed
588 589 590 591 592 593
            wps.append(wp);
        }
    }
    return wps;
}

594
const QList<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
LM's avatar
LM committed
595 596 597 598
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
599
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
600
    foreach (Waypoint* wp, waypointsEditable)
601 602 603
    {
        if (wp->isNavigationType())
        {
LM's avatar
LM committed
604 605 606 607 608 609
            wps.append(wp);
        }
    }
    return wps;
}

610 611
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
612
    return waypointsEditable.indexOf(wp);
613 614
}

615 616
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
617
    // Search through all waypointsEditable,
618 619
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
620
    foreach (Waypoint* p, waypointsEditable) {
621 622 623 624
        if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
            if (p == wp)
            {
625 626 627 628 629 630 631 632 633
                return i;
            }
            i++;
        }
    }

    return -1;
}

lm's avatar
lm committed
634 635
int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
636
    // Search through all waypointsEditable,
lm's avatar
lm committed
637 638
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
639
    foreach (Waypoint* p, waypointsEditable) {
640
        if ((p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
641 642 643
        {
            if (p == wp)
            {
lm's avatar
lm committed
644 645 646 647 648 649 650 651 652
                return i;
            }
            i++;
        }
    }

    return -1;
}

LM's avatar
LM committed
653 654
int UASWaypointManager::getNavTypeIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
655
    // Search through all waypointsEditable,
LM's avatar
LM committed
656 657
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
658
    foreach (Waypoint* p, waypointsEditable)
659 660 661 662 663
    {
        if (p->isNavigationType())
        {
            if (p == wp)
            {
LM's avatar
LM committed
664 665 666 667 668 669 670 671 672
                return i;
            }
            i++;
        }
    }

    return -1;
}

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

    return i;
}

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

    return i;
}

LM's avatar
LM committed
704 705
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
706
    // Search through all waypointsEditable,
LM's avatar
LM committed
707 708
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
709
    foreach (Waypoint* p, waypointsEditable) {
LM's avatar
LM committed
710 711 712 713 714 715 716 717
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

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

    return i;
}

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

    return -1;
}

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

    return -1;
}

pixhawk's avatar
pixhawk committed
774 775 776 777 778

/**
 * @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)
779
{
pixhawk's avatar
pixhawk committed
780
    read_to_edit = readToEdit;
781
    emit readGlobalWPFromUAS(true);
782
    if(current_state == WP_IDLE) {
783

784

785 786
        //Clear the old view-list before receiving the new one
        while(waypointsViewOnly.size()>0) {
787
            Waypoint *t = waypointsViewOnly[0];
788
            waypointsViewOnly.removeAt(0);
789
            delete t;
790
        }
791 792
        emit waypointViewOnlyListChanged();
        /* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
793 794
        //Clear the old edit-list before receiving the new one
        if (read_to_edit == true){
795
            while(waypointsEditable.count()>0) {
796 797 798
                Waypoint *t = waypointsEditable[0];
                waypointsEditable.remove(0);
                delete t;
799
            }
800
            emit waypointEditableListChanged();
801
        }
802
        */
803 804
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
805 806 807

        current_state = WP_GETLIST;
        current_wp_id = 0;
808
        current_partner_systemid = uasid;
lm's avatar
lm committed
809
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
810

811
        sendWaypointRequestList();
812

pixhawk's avatar
pixhawk committed
813 814
    }
}
815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848
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
849

850
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
851
{
852
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
853
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
854
        if (waypointsEditable.count() > 0) {
pixhawk's avatar
pixhawk committed
855
            protocol_timer.start(PROTOCOL_TIMEOUT_MS);
856
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
857

pixhawk's avatar
pixhawk committed
858
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
859 860
            current_state = WP_SENDLIST;
            current_wp_id = 0;
861
            current_partner_systemid = uasid;
lm's avatar
lm committed
862
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
863 864

            //clear local buffer
pixhawk's avatar
pixhawk committed
865 866 867
            // 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.
868
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
869 870 871
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
872

873 874
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
875
            //copy waypoint data to local buffer
876
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
877 878 879
                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
880
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
881 882

                cur_d->autocontinue = cur_s->getAutoContinue();
883
                cur_d->current = cur_s->getCurrent() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
884 885
                cur_d->param1 = cur_s->getParam1();
                cur_d->param2 = cur_s->getParam2();
lm's avatar
lm committed
886 887
                cur_d->param3 = cur_s->getParam3();
                cur_d->param4 = cur_s->getParam4();
888
                cur_d->frame = cur_s->getFrame();
lm's avatar
lm committed
889
                cur_d->command = cur_s->getAction();
890
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
pixhawk's avatar
pixhawk committed
891 892 893
                cur_d->x = cur_s->getX();
                cur_d->y = cur_s->getY();
                cur_d->z = cur_s->getZ();
894 895 896

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
897 898
                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
899
            }
900

901 902 903



pixhawk's avatar
pixhawk committed
904
            //send the waypoint count to UAS (this starts the send transaction)
905
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
906
        } else if (waypointsEditable.count() == 0)
907 908 909
        {
            sendWaypointClearAll();
        }
Lorenz Meier's avatar
Lorenz Meier committed
910 911 912
    }
    else
    {
913
        //we're in another transaction, ignore command
914
        qDebug() << "UASWaypointManager::sendWaypoints() doing something else ignoring command";
915
    }
pixhawk's avatar
pixhawk committed
916 917
}

918 919
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
920
    if (!uas) return;
921
    mavlink_message_t message;
lm's avatar
lm committed
922
    mavlink_mission_clear_all_t wpca;
923

924
    wpca.target_system = uasid;
lm's avatar
lm committed
925
    wpca.target_component = MAV_COMP_ID_MISSIONPLANNER;
926

927
    emit updateStatusString(QString("Clearing waypoint list..."));
928

lm's avatar
lm committed
929
    mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
930

931
    uas->sendMessage(message);
lm's avatar
lm committed
932
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
933 934 935 936
}

void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
{
lm's avatar
lm committed
937
    if (!uas) return;
938
    mavlink_message_t message;
lm's avatar
lm committed
939
    mavlink_mission_set_current_t wpsc;
940

941
    wpsc.target_system = uasid;
lm's avatar
lm committed
942
    wpsc.target_component = MAV_COMP_ID_MISSIONPLANNER;
943 944
    wpsc.seq = seq;

945
    emit updateStatusString(QString("Updating target waypoint..."));
946

lm's avatar
lm committed
947
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
948
    uas->sendMessage(message);
lm's avatar
lm committed
949
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
950 951 952 953
}

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
954
    if (!uas) return;
955
    mavlink_message_t message;
lm's avatar
lm committed
956
    mavlink_mission_count_t wpc;
957

958
    wpc.target_system = uasid;
lm's avatar
lm committed
959
    wpc.target_component = MAV_COMP_ID_MISSIONPLANNER;
960 961
    wpc.count = current_count;

962
    emit updateStatusString(QString("Starting to transmit waypoints..."));
963

lm's avatar
lm committed
964
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
965
    uas->sendMessage(message);
lm's avatar
lm committed
966
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
967 968 969 970
}

void UASWaypointManager::sendWaypointRequestList()
{
lm's avatar
lm committed
971
    if (!uas) return;
972
    mavlink_message_t message;
lm's avatar
lm committed
973
    mavlink_mission_request_list_t wprl;
974

975
    wprl.target_system = uasid;
lm's avatar
lm committed
976
    wprl.target_component = MAV_COMP_ID_MISSIONPLANNER;
977

978 979 980
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
981

lm's avatar
lm committed
982
    mavlink_msg_mission_request_list_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wprl);
983
    uas->sendMessage(message);
lm's avatar
lm committed
984
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
985 986
}

987
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
988
{
lm's avatar
lm committed
989
    if (!uas) return;
990
    mavlink_message_t message;
lm's avatar
lm committed
991
    mavlink_mission_request_t wpr;
992

993
    wpr.target_system = uasid;
lm's avatar
lm committed
994
    wpr.target_component = MAV_COMP_ID_MISSIONPLANNER;
995 996
    wpr.seq = seq;

997
    emit updateStatusString(QString("Retrieving waypoint ID %1 of %2 total").arg(wpr.seq).arg(current_count));
pixhawk's avatar
pixhawk committed
998

lm's avatar
lm committed
999
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1000
    uas->sendMessage(message);
lm's avatar
lm committed
1001
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1002
}
pixhawk's avatar
pixhawk committed
1003

pixhawk's avatar
pixhawk committed
1004 1005
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1006
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1007
    mavlink_message_t message;
1008

1009
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1010

lm's avatar
lm committed
1011
        mavlink_mission_item_t *wp;
1012

pixhawk's avatar
pixhawk committed
1013 1014

        wp = waypoint_buffer.at(seq);
1015
        wp->target_system = uasid;
lm's avatar
lm committed
1016
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1017

1018
        emit updateStatusString(QString("Sending waypoint ID %1 of %2 total").arg(wp->seq).arg(current_count));
1019

pixhawk's avatar
pixhawk committed
1020

lm's avatar
lm committed
1021
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);
1022
        uas->sendMessage(message);
lm's avatar
lm committed
1023
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1024
    }
pixhawk's avatar
pixhawk committed
1025
}
1026 1027 1028

void UASWaypointManager::sendWaypointAck(quint8 type)
{
lm's avatar
lm committed
1029
    if (!uas) return;
1030
    mavlink_message_t message;
lm's avatar
lm committed
1031
    mavlink_mission_ack_t wpa;
1032

1033
    wpa.target_system = uasid;
lm's avatar
lm committed
1034
    wpa.target_component = MAV_COMP_ID_MISSIONPLANNER;
1035 1036
    wpa.type = type;

lm's avatar
lm committed
1037
    mavlink_msg_mission_ack_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpa);
1038
    uas->sendMessage(message);
lm's avatar
lm committed
1039
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1040
}
1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065

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