UASWaypointManager.cc 36.5 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
    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 227 228
            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()));
229 230
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261
            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;
262 263 264
            }
            protocol_timer.stop();
            current_state = WP_IDLE;
265
        } else if(current_state == WP_CLEARLIST) {
266 267
            protocol_timer.stop();
            current_state = WP_IDLE;
268 269
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
270
        }
271 272 273
    }
}

lm's avatar
lm committed
274
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
275
{
276
    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)))) {
277 278
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
        current_retries = PROTOCOL_MAX_RETRIES;
279

280
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
281 282 283
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
284
        } else {
pixhawk's avatar
pixhawk committed
285 286
            //TODO: Error message or something
        }
287
    } else {
288
        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);
289
    }
290 291
}

lm's avatar
lm committed
292
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
293
{
294
	Q_UNUSED(compId);
lm's avatar
lm committed
295
    if (!uas) return;
296
    if (systemId == uasid) {
297
        emit updateStatusString(tr("Reached waypoint %1").arg(wpr->seq));
pixhawk's avatar
pixhawk committed
298
    }
pixhawk's avatar
pixhawk committed
299 300
}

lm's avatar
lm committed
301
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
302
{
303
    Q_UNUSED(compId);
lm's avatar
lm committed
304
    if (!uas) return;
305
    if (systemId == uasid) {
306
        // FIXME Petri
307
        if (current_state == WP_SETCURRENT) {
308 309
            protocol_timer.stop();
            current_state = WP_IDLE;
310 311

            // update the local main storage
pixhawk's avatar
pixhawk committed
312 313 314 315
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
                    if (waypointsViewOnly[i]->getId() == wpc->seq) {
                        waypointsViewOnly[i]->setCurrent(true);
316
                    } else {
pixhawk's avatar
pixhawk committed
317
                        waypointsViewOnly[i]->setCurrent(false);
318 319 320
                    }
                }
            }
321
        }
322
        emit updateStatusString(tr("New current waypoint %1").arg(wpc->seq));
323 324
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
325
    }
pixhawk's avatar
pixhawk committed
326 327
}

328
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
329
{
330
    // If only one waypoint was changed, emit only WP signal
331
    if (wp != NULL) {
332
        emit waypointEditableChanged(uasid, wp);
333
    } else {
334
        emit waypointEditableListChanged();
335
        emit waypointEditableListChanged(uasid);
336
    }
337 338
}

339 340 341
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
342
        emit waypointViewOnlyChanged(uasid, wp);
343 344
    } else {
        emit waypointViewOnlyListChanged();
345
        emit waypointViewOnlyListChanged(uasid);
346 347
    }
}
348 349


350
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
351
{
pixhawk's avatar
pixhawk committed
352
    if (seq < waypointsViewOnly.size()) {
353
        if(current_state == WP_IDLE) {
354

355 356 357 358 359 360
            //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;
361
            current_partner_systemid = uasid;
lm's avatar
lm committed
362
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
363 364 365 366 367 368 369 370 371

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

372 373
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
374
    if (seq < waypointsEditable.count()) {
375 376
        if(current_state == WP_IDLE) {
            //update local main storage
377
            for (int i = 0; i < waypointsEditable.count(); i++) {
378 379 380 381 382 383 384 385 386 387 388 389
                if (waypointsEditable[i]->getId() == seq) {
                    waypointsEditable[i]->setCurrent(true);
                } else {
                    waypointsEditable[i]->setCurrent(false);
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
390 391 392 393

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
394
    {
pixhawk's avatar
pixhawk committed
395 396 397 398
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
399
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
400 401 402 403
    }
}


pixhawk's avatar
pixhawk committed
404
/**
405
 * @warning Make sure the waypoint stays valid for the whole application lifecycle!
pixhawk's avatar
pixhawk committed
406
 * @param enforceFirstActive Enforces that the first waypoint is set as active
407
 * @see createWaypoint() is more suitable for most use cases
pixhawk's avatar
pixhawk committed
408
 */
409
void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive)
410
{
lm's avatar
lm committed
411 412
    if (wp)
    {
413 414 415 416
        // 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."));

417 418
        wp->setId(waypointsEditable.count());
        if (enforceFirstActive && waypointsEditable.count() == 0)
419 420
        {
            wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
421
            currentWaypointEditable = wp;
422
        }
423
        waypointsEditable.insert(waypointsEditable.count(), wp);
424
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
425

426
        emit waypointEditableListChanged();
427
        emit waypointEditableListChanged(uasid);
428
    }
pixhawk's avatar
pixhawk committed
429 430
}

431 432 433 434 435
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
436 437 438 439
    // 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."));

440
    Waypoint* wp = new Waypoint();
441 442 443
    wp->setId(waypointsEditable.count());
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
444
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
445
    if (enforceFirstActive && waypointsEditable.count() == 0)
446 447
    {
        wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
448
        currentWaypointEditable = wp;
449
    }
450
    waypointsEditable.append(wp);
451
    connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
452

453
    emit waypointEditableListChanged();
454
    emit waypointEditableListChanged(uasid);
455 456 457
    return wp;
}

458
int UASWaypointManager::removeWaypoint(quint16 seq)
459
{
460
    if (seq < waypointsEditable.count())
461
    {
pixhawk's avatar
pixhawk committed
462
        Waypoint *t = waypointsEditable[seq];
463 464 465

        if (t->getCurrent() == true) //trying to remove the current waypoint
        {
466
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
467 468 469
            {
                waypointsEditable[seq+1]->setCurrent(true);
            }
470
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
471 472 473 474 475
            {
                waypointsEditable[seq-1]->setCurrent(true);
            }
        }

476
        waypointsEditable.removeAt(seq);
477
        delete t;
478
        t = NULL;
479

480
        for(int i = seq; i < waypointsEditable.count(); i++)
481
        {
pixhawk's avatar
pixhawk committed
482
            waypointsEditable[i]->setId(i);
483
        }
Alejandro's avatar
Alejandro committed
484

485
        emit waypointEditableListChanged();
486
        emit waypointEditableListChanged(uasid);
487 488 489 490 491
        return 0;
    }
    return -1;
}

492
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
493
{
494
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
495
    {
pixhawk's avatar
pixhawk committed
496
        Waypoint *t = waypointsEditable[cur_seq];
497
        if (cur_seq < new_seq) {
498 499
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
500
                waypointsEditable[i] = waypointsEditable[i+1];
501
                waypointsEditable[i]->setId(i);
502
            }
503 504 505 506 507
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
508
                waypointsEditable[i] = waypointsEditable[i-1];
509
                waypointsEditable[i]->setId(i);
510 511
            }
        }
pixhawk's avatar
pixhawk committed
512
        waypointsEditable[new_seq] = t;
513
        waypointsEditable[new_seq]->setId(new_seq);
514

515
        emit waypointEditableListChanged();
516
        emit waypointEditableListChanged(uasid);
517 518 519
    }
}

520
void UASWaypointManager::saveWaypoints(const QString &saveFile)
521 522 523 524 525 526
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
527 528

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

531
    for (int i = 0; i < waypointsEditable.count(); i++)
532
    {
pixhawk's avatar
pixhawk committed
533 534
        waypointsEditable[i]->setId(i);
        waypointsEditable[i]->save(out);
535 536 537 538
    }
    file.close();
}

539
void UASWaypointManager::loadWaypoints(const QString &loadFile)
540 541 542 543 544
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

545
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
546
        Waypoint *t = waypointsEditable[0];
547
        waypointsEditable.removeAt(0);
548 549 550 551
        delete t;
    }

    QTextStream in(&file);
552 553 554

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

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

577 578
    file.close();

579
    emit loadWPFile();
580
    emit waypointEditableListChanged();
581
    emit waypointEditableListChanged(uasid);
582 583 584
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
585
{
586
    if (current_state == WP_IDLE)
587
    {
pixhawk's avatar
pixhawk committed
588
        protocol_timer.start(PROTOCOL_TIMEOUT_MS);
589
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
590

591 592
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
593
        current_partner_systemid = uasid;
lm's avatar
lm committed
594
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
595

596
        sendWaypointClearAll();
597 598 599
    }
}

600
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
601 602 603 604
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
605
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
606
    foreach (Waypoint* wp, waypointsEditable)
607 608 609
    {
        if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
610 611 612 613 614 615
            wps.append(wp);
        }
    }
    return wps;
}

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

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

648 649
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
650
    return waypointsEditable.indexOf(wp);
651 652
}

653 654
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
655
    // Search through all waypointsEditable,
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
        if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
            if (p == wp)
            {
663 664 665 666 667 668 669 670 671
                return i;
            }
            i++;
        }
    }

    return -1;
}

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

    return -1;
}

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

    return -1;
}

711 712
int UASWaypointManager::getGlobalFrameCount()
{
pixhawk's avatar
pixhawk committed
713
    // Search through all waypointsEditable,
714 715
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
716
    foreach (Waypoint* p, waypointsEditable)
717
    {
718 719
        if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
720 721 722 723 724 725 726
            i++;
        }
    }

    return i;
}

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

    return i;
}

LM's avatar
LM committed
742 743
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
744
    // Search through all waypointsEditable,
LM's avatar
LM committed
745 746
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
747
    foreach (Waypoint* p, waypointsEditable) {
LM's avatar
LM committed
748 749 750 751 752 753 754 755
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

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

    return i;
}

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

    return -1;
}

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

    return -1;
}

pixhawk's avatar
pixhawk committed
812 813 814 815 816

/**
 * @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)
817
{
pixhawk's avatar
pixhawk committed
818
    read_to_edit = readToEdit;
819
    emit readGlobalWPFromUAS(true);
820
    if(current_state == WP_IDLE) {
821

822

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

        current_state = WP_GETLIST;
        current_wp_id = 0;
846
        current_partner_systemid = uasid;
lm's avatar
lm committed
847
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
848

849
        sendWaypointRequestList();
850

pixhawk's avatar
pixhawk committed
851 852
    }
}
853 854 855 856 857 858 859 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
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
887

888
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
889
{
890
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
891
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
892
        if (waypointsEditable.count() > 0) {
pixhawk's avatar
pixhawk committed
893
            protocol_timer.start(PROTOCOL_TIMEOUT_MS);
894
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
895

pixhawk's avatar
pixhawk committed
896
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
897 898
            current_state = WP_SENDLIST;
            current_wp_id = 0;
899
            current_partner_systemid = uasid;
lm's avatar
lm committed
900
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
901 902

            //clear local buffer
pixhawk's avatar
pixhawk committed
903 904 905
            // 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.
906
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
907 908 909
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
910

911 912
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
913
            //copy waypoint data to local buffer
914
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
915 916 917
                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
918
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
919 920

                cur_d->autocontinue = cur_s->getAutoContinue();
921
                cur_d->current = cur_s->getCurrent() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
922 923
                cur_d->param1 = cur_s->getParam1();
                cur_d->param2 = cur_s->getParam2();
lm's avatar
lm committed
924 925
                cur_d->param3 = cur_s->getParam3();
                cur_d->param4 = cur_s->getParam4();
926
                cur_d->frame = cur_s->getFrame();
lm's avatar
lm committed
927
                cur_d->command = cur_s->getAction();
928
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
pixhawk's avatar
pixhawk committed
929 930 931
                cur_d->x = cur_s->getX();
                cur_d->y = cur_s->getY();
                cur_d->z = cur_s->getZ();
932 933 934

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
935 936
                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
937
            }
938

939 940 941



pixhawk's avatar
pixhawk committed
942
            //send the waypoint count to UAS (this starts the send transaction)
943
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
944
        } else if (waypointsEditable.count() == 0)
945
        {
946
            clearWaypointList();
947
        }
Lorenz Meier's avatar
Lorenz Meier committed
948 949 950
    }
    else
    {
951 952
        // We're in another transaction, ignore command
        qDebug() << tr("UASWaypointManager::sendWaypoints() doing something else. Ignoring command");
953
    }
pixhawk's avatar
pixhawk committed
954 955
}

956 957
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
958
    if (!uas) return;
959

960 961 962
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
963
    mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
964
    uas->sendMessage(message);
965 966 967 968

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

lm's avatar
lm committed
969
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
970 971 972 973
}

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

976 977 978
    // 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
979
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
980
    uas->sendMessage(message);
981 982 983 984

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

lm's avatar
lm committed
985
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
986 987 988 989
}

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
990
    if (!uas) return;
991 992


993 994 995
    // 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
996
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
997
    uas->sendMessage(message);
998 999 1000 1001

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

lm's avatar
lm committed
1002
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1003 1004 1005 1006
}

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

1009 1010 1011 1012 1013
    // 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);
1014

1015
    // And update the UI.
1016 1017 1018
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1019

lm's avatar
lm committed
1020
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1021 1022
}

1023
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1024
{
lm's avatar
lm committed
1025
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1026

1027 1028 1029
    // 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
1030
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1031
    uas->sendMessage(message);
1032 1033 1034 1035

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

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

pixhawk's avatar
pixhawk committed
1039 1040
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1041
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1042
    mavlink_message_t message;
1043

1044
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1045

1046 1047
        // Fetch the current mission to send, and set it to apply to the curent UAS.
        mavlink_mission_item_t *wp = waypoint_buffer.at(seq);
1048
        wp->target_system = uasid;
lm's avatar
lm committed
1049
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1050

1051
        // Transmit the new mission
lm's avatar
lm committed
1052
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);
1053
        uas->sendMessage(message);
1054 1055 1056 1057

        // 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
1058
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1059
    }
pixhawk's avatar
pixhawk committed
1060
}
1061 1062 1063

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

1066 1067 1068
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
lm's avatar
lm committed
1069
    mavlink_msg_mission_ack_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpa);
1070
    uas->sendMessage(message);
1071

lm's avatar
lm committed
1072
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1073
}
1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098

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()
{
1099 1100
    if (waypointsEditable.count() > 0)
    {
1101 1102
        return waypointsEditable.last()->getAcceptanceRadius();
    }
1103 1104 1105 1106
    else
    {
        if (uas->isRotaryWing())
        {
Thomas Gubler's avatar
Thomas Gubler committed
1107 1108 1109 1110 1111 1112
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
        else if (uas->isFixedWing())
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1113 1114 1115
    }

    return 10.0f;
1116 1117 1118 1119 1120 1121
}

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