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

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

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

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

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

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

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

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

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

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

38
#define PROTOCOL_TIMEOUT_MS 2000    ///< maximum time to wait for pending messages until timeout
lm's avatar
lm committed
39 40
#define PROTOCOL_DELAY_MS 20        ///< minimum delay between sent messages
#define PROTOCOL_MAX_RETRIES 5      ///< maximum number of send retries (after timeout)
41
const float UASWaypointManager::defaultAltitudeHomeOffset   = 30.0f;
lm's avatar
lm committed
42
UASWaypointManager::UASWaypointManager(UAS* _uas)
43 44 45 46 47 48 49
    : uas(_uas),
      current_retries(0),
      current_wp_id(0),
      current_count(0),
      current_state(WP_IDLE),
      current_partner_systemid(0),
      current_partner_compid(0),
50 51
      currentWaypointEditable(NULL),
      protocol_timer(this)
pixhawk's avatar
pixhawk committed
52
{
53 54
    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();
156 157
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
158 159 160 161 162
            current_state = WP_IDLE;
            current_count = 0;
            current_wp_id = 0;
            current_partner_systemid = 0;
            current_partner_compid = 0;
pixhawk's avatar
pixhawk committed
163
        }
164 165


166
    } else {
167
        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);
168
    }
169 170
}

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

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

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

            //get next waypoint
            current_wp_id++;

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

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

pixhawk's avatar
pixhawk committed
205
                protocol_timer.stop();
206
                emit readGlobalWPFromUAS(false);
207
                QTime time = QTime::currentTime();
208
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
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
    } else {
215
        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);
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 222 223 224 225 226 227 228 229 230
    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) {
231
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
232 233
            //all waypoints sent and ack received
            protocol_timer.stop();
234
            current_state = WP_IDLE;
235 236 237
            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()));
238 239
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270
            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;
271 272 273
            }
            protocol_timer.stop();
            current_state = WP_IDLE;
274
        } else if(current_state == WP_CLEARLIST) {
275 276
            protocol_timer.stop();
            current_state = WP_IDLE;
277 278
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
279
        }
280 281 282
    }
}

lm's avatar
lm committed
283
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
284
{
285
    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)))) {
286 287
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries = PROTOCOL_MAX_RETRIES;
288

289
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
290 291 292
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
293
        } else {
pixhawk's avatar
pixhawk committed
294 295
            //TODO: Error message or something
        }
296
    } else {
297
        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);
298
    }
299 300
}

lm's avatar
lm committed
301
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
302
{
303
	Q_UNUSED(compId);
lm's avatar
lm committed
304
    if (!uas) return;
305
    if (systemId == uasid) {
306
        emit updateStatusString(tr("Reached waypoint %1").arg(wpr->seq));
pixhawk's avatar
pixhawk committed
307
    }
pixhawk's avatar
pixhawk committed
308 309
}

lm's avatar
lm committed
310
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
311
{
312
    Q_UNUSED(compId);
lm's avatar
lm committed
313
    if (!uas) return;
314
    if (systemId == uasid) {
315
        // FIXME Petri
316
        if (current_state == WP_SETCURRENT) {
317 318
            protocol_timer.stop();
            current_state = WP_IDLE;
319 320

            // update the local main storage
pixhawk's avatar
pixhawk committed
321 322 323 324
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
                    if (waypointsViewOnly[i]->getId() == wpc->seq) {
                        waypointsViewOnly[i]->setCurrent(true);
325
                    } else {
pixhawk's avatar
pixhawk committed
326
                        waypointsViewOnly[i]->setCurrent(false);
327 328 329
                    }
                }
            }
330
        }
331
        emit updateStatusString(tr("New current waypoint %1").arg(wpc->seq));
332 333
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
334
    }
pixhawk's avatar
pixhawk committed
335 336
}

337
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
338
{
339
    // If only one waypoint was changed, emit only WP signal
340
    if (wp != NULL) {
341
        emit waypointEditableChanged(uasid, wp);
342
    } else {
343
        emit waypointEditableListChanged();
344
        emit waypointEditableListChanged(uasid);
345
    }
346 347
}

348 349 350
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
351
        emit waypointViewOnlyChanged(uasid, wp);
352 353
    } else {
        emit waypointViewOnlyListChanged();
354
        emit waypointViewOnlyListChanged(uasid);
355 356
    }
}
357 358


359
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
360
{
pixhawk's avatar
pixhawk committed
361
    if (seq < waypointsViewOnly.size()) {
362
        if(current_state == WP_IDLE) {
363

364 365 366 367 368 369
            //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;
370
            current_partner_systemid = uasid;
lm's avatar
lm committed
371
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
372 373 374 375 376 377 378 379 380

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

381 382
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
383
    if (seq < waypointsEditable.count()) {
384 385
        if(current_state == WP_IDLE) {
            //update local main storage
386
            for (int i = 0; i < waypointsEditable.count(); i++) {
387 388 389 390 391 392 393 394 395 396 397 398
                if (waypointsEditable[i]->getId() == seq) {
                    waypointsEditable[i]->setCurrent(true);
                } else {
                    waypointsEditable[i]->setCurrent(false);
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
399 400 401 402

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
403
    {
pixhawk's avatar
pixhawk committed
404 405 406 407
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
408
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
409 410 411 412
    }
}


pixhawk's avatar
pixhawk committed
413
/**
414
 * @warning Make sure the waypoint stays valid for the whole application lifecycle!
pixhawk's avatar
pixhawk committed
415
 * @param enforceFirstActive Enforces that the first waypoint is set as active
416
 * @see createWaypoint() is more suitable for most use cases
pixhawk's avatar
pixhawk committed
417
 */
418
void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive)
419
{
lm's avatar
lm committed
420 421
    if (wp)
    {
422 423 424 425
        // 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."));

426 427
        wp->setId(waypointsEditable.count());
        if (enforceFirstActive && waypointsEditable.count() == 0)
428 429
        {
            wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
430
            currentWaypointEditable = wp;
431
        }
432
        waypointsEditable.insert(waypointsEditable.count(), wp);
433
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
434

435
        emit waypointEditableListChanged();
436
        emit waypointEditableListChanged(uasid);
437
    }
pixhawk's avatar
pixhawk committed
438 439
}

440 441 442 443 444
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
445 446 447 448
    // 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."));

449
    Waypoint* wp = new Waypoint();
450 451 452
    wp->setId(waypointsEditable.count());
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
453
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
454
    if (enforceFirstActive && waypointsEditable.count() == 0)
455 456
    {
        wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
457
        currentWaypointEditable = wp;
458
    }
459
    waypointsEditable.append(wp);
460
    connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
461

462
    emit waypointEditableListChanged();
463
    emit waypointEditableListChanged(uasid);
464 465 466
    return wp;
}

467
int UASWaypointManager::removeWaypoint(quint16 seq)
468
{
469
    if (seq < waypointsEditable.count())
470
    {
pixhawk's avatar
pixhawk committed
471
        Waypoint *t = waypointsEditable[seq];
472 473 474

        if (t->getCurrent() == true) //trying to remove the current waypoint
        {
475
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
476 477 478
            {
                waypointsEditable[seq+1]->setCurrent(true);
            }
479
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
480 481 482 483 484
            {
                waypointsEditable[seq-1]->setCurrent(true);
            }
        }

485
        waypointsEditable.removeAt(seq);
486
        delete t;
487
        t = NULL;
488

489
        for(int i = seq; i < waypointsEditable.count(); i++)
490
        {
pixhawk's avatar
pixhawk committed
491
            waypointsEditable[i]->setId(i);
492
        }
Alejandro's avatar
Alejandro committed
493

494
        emit waypointEditableListChanged();
495
        emit waypointEditableListChanged(uasid);
496 497 498 499 500
        return 0;
    }
    return -1;
}

501
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
502
{
503
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
504
    {
pixhawk's avatar
pixhawk committed
505
        Waypoint *t = waypointsEditable[cur_seq];
506
        if (cur_seq < new_seq) {
507 508
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
509
                waypointsEditable[i] = waypointsEditable[i+1];
510
                waypointsEditable[i]->setId(i);
511
            }
512 513 514 515 516
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
517
                waypointsEditable[i] = waypointsEditable[i-1];
518
                waypointsEditable[i]->setId(i);
519 520
            }
        }
pixhawk's avatar
pixhawk committed
521
        waypointsEditable[new_seq] = t;
522
        waypointsEditable[new_seq]->setId(new_seq);
523

524
        emit waypointEditableListChanged();
525
        emit waypointEditableListChanged(uasid);
526 527 528
    }
}

529
void UASWaypointManager::saveWaypoints(const QString &saveFile)
530 531 532 533 534 535
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
536 537

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

540
    for (int i = 0; i < waypointsEditable.count(); i++)
541
    {
pixhawk's avatar
pixhawk committed
542 543
        waypointsEditable[i]->setId(i);
        waypointsEditable[i]->save(out);
544 545 546 547
    }
    file.close();
}

548
void UASWaypointManager::loadWaypoints(const QString &loadFile)
549 550 551 552 553
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

554
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
555
        Waypoint *t = waypointsEditable[0];
556
        waypointsEditable.removeAt(0);
557 558 559 560
        delete t;
    }

    QTextStream in(&file);
561 562 563

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

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

586 587
    file.close();

588
    emit loadWPFile();
589
    emit waypointEditableListChanged();
590
    emit waypointEditableListChanged(uasid);
591 592 593
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
594
{
595
    if (current_state == WP_IDLE)
596
    {
pixhawk's avatar
pixhawk committed
597
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
598
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
599

600 601
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
602
        current_partner_systemid = uasid;
lm's avatar
lm committed
603
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
604

605
        sendWaypointClearAll();
606 607 608
    }
}

609
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
610 611 612 613
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
614
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
615
    foreach (Waypoint* wp, waypointsEditable)
616 617 618
    {
        if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
619 620 621 622 623 624
            wps.append(wp);
        }
    }
    return wps;
}

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

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

657 658
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
659
    return waypointsEditable.indexOf(wp);
660 661
}

662 663
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
664
    // Search through all waypointsEditable,
665 666
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
667
    foreach (Waypoint* p, waypointsEditable) {
668 669 670 671
        if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
            if (p == wp)
            {
672 673 674 675 676 677 678 679 680
                return i;
            }
            i++;
        }
    }

    return -1;
}

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

    return -1;
}

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

    return -1;
}

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

    return i;
}

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

    return i;
}

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

    return i;
}

765 766
int UASWaypointManager::getLocalFrameCount()
{
pixhawk's avatar
pixhawk committed
767
    // Search through all waypointsEditable,
768 769
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
770
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
771
    {
772
        if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
lm's avatar
lm committed
773
        {
774 775 776 777 778 779 780 781 782
            i++;
        }
    }

    return i;
}

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

    return -1;
}

int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
803
    // Search through all waypointsEditable,
804 805
    // counting only those in mission frame
    int i = 0;
pixhawk's avatar
pixhawk committed
806
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
807
    {
808 809 810 811
        if (p->getFrame() == MAV_FRAME_MISSION)
        {
            if (p == wp)
            {
812 813 814 815 816 817 818 819 820
                return i;
            }
            i++;
        }
    }

    return -1;
}

pixhawk's avatar
pixhawk committed
821 822 823 824 825

/**
 * @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)
826
{
pixhawk's avatar
pixhawk committed
827
    read_to_edit = readToEdit;
828
    emit readGlobalWPFromUAS(true);
829
    if(current_state == WP_IDLE) {
830

831

832 833
        //Clear the old view-list before receiving the new one
        while(waypointsViewOnly.size()>0) {
834
            Waypoint *t = waypointsViewOnly[0];
835
            waypointsViewOnly.removeAt(0);
836
            delete t;
837
        }
838 839
        emit waypointViewOnlyListChanged();
        /* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
840 841
        //Clear the old edit-list before receiving the new one
        if (read_to_edit == true){
842
            while(waypointsEditable.count()>0) {
843 844 845
                Waypoint *t = waypointsEditable[0];
                waypointsEditable.remove(0);
                delete t;
846
            }
847
            emit waypointEditableListChanged();
848
        }
849
        */
850 851
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
852 853 854

        current_state = WP_GETLIST;
        current_wp_id = 0;
855
        current_partner_systemid = uasid;
lm's avatar
lm committed
856
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
857

858
        sendWaypointRequestList();
859

pixhawk's avatar
pixhawk committed
860 861
    }
}
862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895
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
896

897
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
898
{
899
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
900
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
901
        if (waypointsEditable.count() > 0) {
pixhawk's avatar
pixhawk committed
902
            protocol_timer.start(PROTOCOL_TIMEOUT_MS);
903
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
904

pixhawk's avatar
pixhawk committed
905
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
906 907
            current_state = WP_SENDLIST;
            current_wp_id = 0;
908
            current_partner_systemid = uasid;
lm's avatar
lm committed
909
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
910 911

            //clear local buffer
pixhawk's avatar
pixhawk committed
912 913 914
            // 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.
915
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
916 917 918
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
919

920 921
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
922
            //copy waypoint data to local buffer
923
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
924 925 926
                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
927
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
928 929

                cur_d->autocontinue = cur_s->getAutoContinue();
930
                cur_d->current = cur_s->getCurrent() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
931 932
                cur_d->param1 = cur_s->getParam1();
                cur_d->param2 = cur_s->getParam2();
lm's avatar
lm committed
933 934
                cur_d->param3 = cur_s->getParam3();
                cur_d->param4 = cur_s->getParam4();
935
                cur_d->frame = cur_s->getFrame();
lm's avatar
lm committed
936
                cur_d->command = cur_s->getAction();
937
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
pixhawk's avatar
pixhawk committed
938 939 940
                cur_d->x = cur_s->getX();
                cur_d->y = cur_s->getY();
                cur_d->z = cur_s->getZ();
941 942 943

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
944 945
                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
946
            }
947

948 949 950



pixhawk's avatar
pixhawk committed
951
            //send the waypoint count to UAS (this starts the send transaction)
952
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
953
        } else if (waypointsEditable.count() == 0)
954
        {
955
            clearWaypointList();
956
        }
Lorenz Meier's avatar
Lorenz Meier committed
957 958 959
    }
    else
    {
960 961
        // We're in another transaction, ignore command
        qDebug() << tr("UASWaypointManager::sendWaypoints() doing something else. Ignoring command");
962
    }
pixhawk's avatar
pixhawk committed
963 964
}

965 966
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
967
    if (!uas) return;
968

969 970 971
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
972
    mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
973
    uas->sendMessage(message);
974 975 976 977

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

lm's avatar
lm committed
978
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
979 980 981 982
}

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

985 986 987
    // 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
988
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
989
    uas->sendMessage(message);
990 991 992 993

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

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

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
999
    if (!uas) return;
1000 1001


1002 1003 1004
    // 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
1005
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1006
    uas->sendMessage(message);
1007 1008 1009 1010

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

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

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

1018 1019 1020 1021 1022
    // 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);
1023

1024
    // And update the UI.
1025 1026 1027
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1028

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

1032
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1033
{
lm's avatar
lm committed
1034
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1035

1036 1037 1038
    // 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
1039
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1040
    uas->sendMessage(message);
1041 1042 1043 1044

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

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

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

1053
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1054

1055 1056
        // Fetch the current mission to send, and set it to apply to the curent UAS.
        mavlink_mission_item_t *wp = waypoint_buffer.at(seq);
1057
        wp->target_system = uasid;
lm's avatar
lm committed
1058
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1059

1060
        // Transmit the new mission
lm's avatar
lm committed
1061
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);
1062
        uas->sendMessage(message);
1063 1064 1065 1066

        // 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
1067
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1068
    }
pixhawk's avatar
pixhawk committed
1069
}
1070 1071 1072

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

1075 1076 1077
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
lm's avatar
lm committed
1078
    mavlink_msg_mission_ack_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpa);
1079
    uas->sendMessage(message);
1080

lm's avatar
lm committed
1081
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1082
}
1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107

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()
{
1108 1109
    if (waypointsEditable.count() > 0)
    {
1110 1111
        return waypointsEditable.last()->getAcceptanceRadius();
    }
1112 1113 1114 1115
    else
    {
        if (uas->isRotaryWing())
        {
Thomas Gubler's avatar
Thomas Gubler committed
1116 1117 1118 1119 1120 1121
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
        else if (uas->isFixedWing())
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1122 1123 1124
    }

    return 10.0f;
1125 1126 1127 1128 1129 1130
}

float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
    return defaultAltitudeHomeOffset;
}