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

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

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

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

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

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

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

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

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

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

38
#define PROTOCOL_TIMEOUT_MS 2000    ///< maximum time to wait for pending messages until timeout
lm's avatar
lm committed
39 40
#define PROTOCOL_DELAY_MS 20        ///< minimum delay between sent messages
#define PROTOCOL_MAX_RETRIES 5      ///< maximum number of send retries (after timeout)
41
const float UASWaypointManager::defaultAltitudeHomeOffset   = 30.0f;
lm's avatar
lm committed
42
UASWaypointManager::UASWaypointManager(UAS* _uas)
43 44 45 46 47 48 49
    : uas(_uas),
      current_retries(0),
      current_wp_id(0),
      current_count(0),
      current_state(WP_IDLE),
      current_partner_systemid(0),
      current_partner_compid(0),
50 51
      currentWaypointEditable(NULL),
      protocol_timer(this)
pixhawk's avatar
pixhawk committed
52
{
53 54
    if (uas)
    {
lm's avatar
lm committed
55 56 57
        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)));
58
        connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,quint64)));
lm's avatar
lm committed
59 60 61 62
    }
    else
    {
        uasid = 0;
63
    }
64 65 66 67
    
    // We signal to ourselves here so that tiemrs are started and stopped on correct thread
    connect(this, SIGNAL(_startProtocolTimer(void)), this, SLOT(_startProtocolTimerOnThisThread(void)));
    connect(this, SIGNAL(_stopProtocolTimer(void)), this, SLOT(_stopProtocolTimerOnThisThread(void)));
pixhawk's avatar
pixhawk committed
68 69
}

LM's avatar
LM committed
70 71 72 73 74
UASWaypointManager::~UASWaypointManager()
{

}

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

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

98
        emit updateStatusString("Operation timed out.");
pixhawk's avatar
pixhawk committed
99

100 101 102 103 104 105
        current_state = WP_IDLE;
        current_count = 0;
        current_wp_id = 0;
        current_partner_systemid = 0;
        current_partner_compid = 0;
    }
106 107
}

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

122
void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double altAMSL, double altWGS84, quint64 time)
123
{
124 125
    Q_UNUSED(mav);
    Q_UNUSED(time);
126 127
    Q_UNUSED(altAMSL);
    Q_UNUSED(altWGS84);
128 129
	Q_UNUSED(lon);
	Q_UNUSED(lat);
130 131 132 133 134 135
    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);
    }
136 137
}

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

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

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


171
    } else {
172
        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);
173
    }
174 175
}

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

182
        if(wp->seq == current_wp_id) {
pixhawk's avatar
pixhawk committed
183 184 185 186 187 188 189 190 191 192 193

            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
194 195 196 197

            //get next waypoint
            current_wp_id++;

198
            if(current_wp_id < current_count) {
199
                sendWaypointRequest(current_wp_id);
200
            } else {
201 202
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
203
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
204 205 206 207 208
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
                current_partner_systemid = 0;
                current_partner_compid = 0;
209

210
                emit _stopProtocolTimer(); // Stop timer on our thread
211
                emit readGlobalWPFromUAS(false);
212
                QTime time = QTime::currentTime();
213
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
214

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

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

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

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

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

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

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

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

353 354 355
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
356
        emit waypointViewOnlyChanged(uasid, wp);
357 358
    } else {
        emit waypointViewOnlyListChanged();
359
        emit waypointViewOnlyListChanged(uasid);
360 361
    }
}
362 363


364
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
365
{
pixhawk's avatar
pixhawk committed
366
    if (seq < waypointsViewOnly.size()) {
367
        if(current_state == WP_IDLE) {
368

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

            current_state = WP_SETCURRENT;
            current_wp_id = seq;
375
            current_partner_systemid = uasid;
lm's avatar
lm committed
376
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
377 378 379 380 381 382 383 384 385

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

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

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
404 405 406 407

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
408
    {
pixhawk's avatar
pixhawk committed
409 410 411 412
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
413
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
414 415 416 417
    }
}


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

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

440
        emit waypointEditableListChanged();
441
        emit waypointEditableListChanged(uasid);
442
    }
pixhawk's avatar
pixhawk committed
443 444
}

445 446 447 448 449
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
450 451 452 453
    // 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."));

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

467
    emit waypointEditableListChanged();
468
    emit waypointEditableListChanged(uasid);
469 470 471
    return wp;
}

472
int UASWaypointManager::removeWaypoint(quint16 seq)
473
{
474
    if (seq < waypointsEditable.count())
475
    {
pixhawk's avatar
pixhawk committed
476
        Waypoint *t = waypointsEditable[seq];
477 478 479

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

490
        waypointsEditable.removeAt(seq);
491
        delete t;
492
        t = NULL;
493

494
        for(int i = seq; i < waypointsEditable.count(); i++)
495
        {
pixhawk's avatar
pixhawk committed
496
            waypointsEditable[i]->setId(i);
497
        }
Alejandro's avatar
Alejandro committed
498

499
        emit waypointEditableListChanged();
500
        emit waypointEditableListChanged(uasid);
501 502 503 504 505
        return 0;
    }
    return -1;
}

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

529
        emit waypointEditableListChanged();
530
        emit waypointEditableListChanged(uasid);
531 532 533
    }
}

534
void UASWaypointManager::saveWaypoints(const QString &saveFile)
535 536 537 538 539 540
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
541 542

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

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

553
void UASWaypointManager::loadWaypoints(const QString &loadFile)
554 555 556 557 558
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

559
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
560
        Waypoint *t = waypointsEditable[0];
561
        waypointsEditable.removeAt(0);
562 563 564 565
        delete t;
    }

    QTextStream in(&file);
566 567 568

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

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

591 592
    file.close();

593
    emit loadWPFile();
594
    emit waypointEditableListChanged();
595
    emit waypointEditableListChanged(uasid);
596 597 598
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
599
{
600
    if (current_state == WP_IDLE)
601
    {
602
        emit _startProtocolTimer(); // Start timer on our thread
603
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
604

605 606
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
607
        current_partner_systemid = uasid;
lm's avatar
lm committed
608
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
609

610
        sendWaypointClearAll();
611 612 613
    }
}

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

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

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

662 663
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
664
    return waypointsEditable.indexOf(wp);
665 666
}

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

    return -1;
}

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

    return -1;
}

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

    return -1;
}

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

    return i;
}

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

    return i;
}

LM's avatar
LM committed
756 757
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
758
    // Search through all waypointsEditable,
LM's avatar
LM committed
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 764 765 766 767 768 769
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

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

    return i;
}

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

    return -1;
}

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

    return -1;
}

pixhawk's avatar
pixhawk committed
826 827 828 829 830

/**
 * @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)
831
{
pixhawk's avatar
pixhawk committed
832
    read_to_edit = readToEdit;
833
    emit readGlobalWPFromUAS(true);
834
    if(current_state == WP_IDLE) {
835

836

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

859
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
860 861 862

        current_state = WP_GETLIST;
        current_wp_id = 0;
863
        current_partner_systemid = uasid;
lm's avatar
lm committed
864
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
865

866
        sendWaypointRequestList();
867

pixhawk's avatar
pixhawk committed
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 896 897 898 899 900 901 902 903
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
904

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

pixhawk's avatar
pixhawk committed
913
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
914 915
            current_state = WP_SENDLIST;
            current_wp_id = 0;
916
            current_partner_systemid = uasid;
lm's avatar
lm committed
917
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
918 919

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

928 929
            bool noCurrent = true;

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

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

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
952 953
                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
954
            }
955

956 957 958



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

973 974
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
975
    if (!uas) return;
976

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

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

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

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

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

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

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

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


1010 1011 1012
    // 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
1013
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1014
    uas->sendMessage(message);
1015 1016 1017 1018

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

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

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

1026 1027 1028 1029 1030
    // 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);
1031

1032
    // And update the UI.
1033 1034 1035
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1036

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

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

1044 1045 1046
    // 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
1047
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1048
    uas->sendMessage(message);
1049 1050 1051 1052

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

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

pixhawk's avatar
pixhawk committed
1056 1057
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1058
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1059
    mavlink_message_t message;
1060

1061
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1062

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

1068
        // Transmit the new mission
lm's avatar
lm committed
1069
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);
1070
        uas->sendMessage(message);
1071 1072 1073 1074

        // 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
1075
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1076
    }
pixhawk's avatar
pixhawk committed
1077
}
1078 1079 1080

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

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

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

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()
{
1116 1117
    if (waypointsEditable.count() > 0)
    {
1118 1119
        return waypointsEditable.last()->getAcceptanceRadius();
    }
1120 1121 1122 1123
    else
    {
        if (uas->isRotaryWing())
        {
Thomas Gubler's avatar
Thomas Gubler committed
1124 1125 1126 1127 1128 1129
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
        else if (uas->isFixedWing())
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1130 1131 1132
    }

    return 10.0f;
1133 1134 1135 1136 1137 1138
}

float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
    return defaultAltitudeHomeOffset;
}
1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149


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

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