UASWaypointManager.cc 38.3 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
      currentWaypointEditable(),
51
      protocol_timer(this)
pixhawk's avatar
pixhawk committed
52
{
53 54 55 56
    
    _offlineEditingModeTitle = tr("OFFLINE Waypoint Editing Mode");
    _offlineEditingModeMessage = tr("You are in offline editing mode. Make sure to save your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect.");
    
57 58
    if (uas)
    {
lm's avatar
lm committed
59 60 61
        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)));
62
        connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,quint64)));
lm's avatar
lm committed
63 64 65 66
    }
    else
    {
        uasid = 0;
67
    }
68 69 70 71
    
    // 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
72 73
}

LM's avatar
LM committed
74 75 76 77 78
UASWaypointManager::~UASWaypointManager()
{

}

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

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

102
        emit updateStatusString("Operation timed out.");
pixhawk's avatar
pixhawk committed
103

104 105 106 107 108 109
        current_state = WP_IDLE;
        current_count = 0;
        current_wp_id = 0;
        current_partner_systemid = 0;
        current_partner_compid = 0;
    }
110 111
}

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

126
void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double altAMSL, double altWGS84, quint64 time)
127
{
128 129
    Q_UNUSED(mav);
    Q_UNUSED(time);
130 131
    Q_UNUSED(altAMSL);
    Q_UNUSED(altWGS84);
132 133
	Q_UNUSED(lon);
	Q_UNUSED(lat);
134
    if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT))
135 136 137 138 139
    {
        // TODO FIXME Calculate distance
        double dist = 0;
        emit waypointDistanceChanged(dist);
    }
140 141
}

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

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

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


175
    } else {
176
        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);
177
    }
178 179
}

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

186
        if(wp->seq == current_wp_id) {
pixhawk's avatar
pixhawk committed
187 188 189 190 191 192 193 194 195 196 197

            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
198 199 200 201

            //get next waypoint
            current_wp_id++;

202
            if(current_wp_id < current_count) {
203
                sendWaypointRequest(current_wp_id);
204
            } else {
205 206
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
207
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
208 209 210 211 212
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
                current_partner_systemid = 0;
                current_partner_compid = 0;
213

214
                emit _stopProtocolTimer(); // Stop timer on our thread
215
                emit readGlobalWPFromUAS(false);
216
                QTime time = QTime::currentTime();
217
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
218

pixhawk's avatar
pixhawk committed
219
            }
220
        } else {
221
            emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
222
        }
223 224 225 226 227 228 229 230 231 232
    } else if (systemId == current_partner_systemid
            && wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->getAction()) {
        // accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions
        // but only update view only side
        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);

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

233
    } else {
234
        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);
235
    }
pixhawk's avatar
pixhawk committed
236 237
}

lm's avatar
lm committed
238
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
239
{
240 241 242 243 244 245 246 247 248 249
    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) {
250
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
251
            //all waypoints sent and ack received
252
            emit _stopProtocolTimer();  // Stop timer on our thread
253
            current_state = WP_IDLE;
254 255 256
            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()));
257 258
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289
            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;
290
            }
291
            emit _stopProtocolTimer();  // Stop timer on our thread
292
            current_state = WP_IDLE;
293
        } else if(current_state == WP_CLEARLIST) {
294
            emit _stopProtocolTimer(); // Stop timer on our thread
295
            current_state = WP_IDLE;
296 297
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
298
        }
299 300 301
    }
}

lm's avatar
lm committed
302
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
303
{
304
    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)))) {
305
        emit _startProtocolTimer();  // Start timer on our thread
306
        current_retries = PROTOCOL_MAX_RETRIES;
307

308
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
309 310 311
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
312
        } else {
pixhawk's avatar
pixhawk committed
313 314
            //TODO: Error message or something
        }
315
    } else {
316
        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);
317
    }
318 319
}

lm's avatar
lm committed
320
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
321
{
322
	Q_UNUSED(compId);
lm's avatar
lm committed
323
    if (!uas) return;
324
    if (systemId == uasid) {
325
        emit updateStatusString(tr("Reached waypoint %1").arg(wpr->seq));
pixhawk's avatar
pixhawk committed
326
    }
pixhawk's avatar
pixhawk committed
327 328
}

lm's avatar
lm committed
329
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
330
{
331
    Q_UNUSED(compId);
lm's avatar
lm committed
332
    if (!uas) return;
333
    if (systemId == uasid) {
334
        // FIXME Petri
335
        if (current_state == WP_SETCURRENT) {
336
            emit _stopProtocolTimer();  // Stop timer on our thread
337
            current_state = WP_IDLE;
338 339

            // update the local main storage
pixhawk's avatar
pixhawk committed
340 341 342 343
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
                    if (waypointsViewOnly[i]->getId() == wpc->seq) {
                        waypointsViewOnly[i]->setCurrent(true);
344
                    } else {
pixhawk's avatar
pixhawk committed
345
                        waypointsViewOnly[i]->setCurrent(false);
346 347 348
                    }
                }
            }
349
        }
350
        emit updateStatusString(tr("New current waypoint %1").arg(wpc->seq));
351 352
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
353
    }
pixhawk's avatar
pixhawk committed
354 355
}

356
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
357
{
358
    // If only one waypoint was changed, emit only WP signal
359
    if (wp != NULL) {
360
        emit waypointEditableChanged(uasid, wp);
361
    } else {
362
        emit waypointEditableListChanged();
363
        emit waypointEditableListChanged(uasid);
364
    }
365 366
}

367 368 369
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
370
        emit waypointViewOnlyChanged(uasid, wp);
371 372
    } else {
        emit waypointViewOnlyListChanged();
373
        emit waypointViewOnlyListChanged(uasid);
374 375
    }
}
376 377


378
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
379
{
pixhawk's avatar
pixhawk committed
380
    if (seq < waypointsViewOnly.size()) {
381
        if(current_state == WP_IDLE) {
382

383
            //send change to UAS - important to note: if the transmission fails, we have inconsistencies
384
            emit _startProtocolTimer();  // Start timer on our thread
385 386 387 388
            current_retries = PROTOCOL_MAX_RETRIES;

            current_state = WP_SETCURRENT;
            current_wp_id = seq;
389
            current_partner_systemid = uasid;
lm's avatar
lm committed
390
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
391 392 393 394 395 396 397 398 399

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

400 401
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
402
    if (seq < waypointsEditable.count()) {
403 404
        if(current_state == WP_IDLE) {
            //update local main storage
405
            for (int i = 0; i < waypointsEditable.count(); i++) {
406 407 408 409 410 411 412 413 414 415 416 417
                if (waypointsEditable[i]->getId() == seq) {
                    waypointsEditable[i]->setCurrent(true);
                } else {
                    waypointsEditable[i]->setCurrent(false);
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
418 419 420 421

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
422
    {
pixhawk's avatar
pixhawk committed
423 424 425 426
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
427
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
428 429 430 431
    }
}


pixhawk's avatar
pixhawk committed
432
/**
433
 * @warning Make sure the waypoint stays valid for the whole application lifecycle!
pixhawk's avatar
pixhawk committed
434
 * @param enforceFirstActive Enforces that the first waypoint is set as active
435
 * @see createWaypoint() is more suitable for most use cases
pixhawk's avatar
pixhawk committed
436
 */
437
void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive)
438
{
lm's avatar
lm committed
439 440
    if (wp)
    {
441 442
        // Check if this is the first waypoint in an offline list
        if (waypointsEditable.count() == 0 && uas == NULL)
443
            MainWindow::instance()->showCriticalMessage(_offlineEditingModeTitle, _offlineEditingModeMessage);
444

445 446
        wp->setId(waypointsEditable.count());
        if (enforceFirstActive && waypointsEditable.count() == 0)
447 448
        {
            wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
449
            currentWaypointEditable = wp;
450
        }
451
        waypointsEditable.insert(waypointsEditable.count(), wp);
452
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
453

454
        emit waypointEditableListChanged();
455
        emit waypointEditableListChanged(uasid);
456
    }
pixhawk's avatar
pixhawk committed
457 458
}

459 460 461 462 463
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
464 465
    // Check if this is the first waypoint in an offline list
    if (waypointsEditable.count() == 0 && uas == NULL)
466
        MainWindow::instance()->showCriticalMessage(_offlineEditingModeTitle, _offlineEditingModeMessage);
467

468
    Waypoint* wp = new Waypoint();
469 470 471
    wp->setId(waypointsEditable.count());
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
472
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
473
    if (enforceFirstActive && waypointsEditable.count() == 0)
474 475
    {
        wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
476
        currentWaypointEditable = wp;
477
    }
478
    waypointsEditable.append(wp);
479
    connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
480

481
    emit waypointEditableListChanged();
482
    emit waypointEditableListChanged(uasid);
483 484 485
    return wp;
}

486
int UASWaypointManager::removeWaypoint(quint16 seq)
487
{
488
    if (seq < waypointsEditable.count())
489
    {
pixhawk's avatar
pixhawk committed
490
        Waypoint *t = waypointsEditable[seq];
491 492 493

        if (t->getCurrent() == true) //trying to remove the current waypoint
        {
494
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
495 496 497
            {
                waypointsEditable[seq+1]->setCurrent(true);
            }
498
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
499 500 501 502 503
            {
                waypointsEditable[seq-1]->setCurrent(true);
            }
        }

504
        waypointsEditable.removeAt(seq);
505
        delete t;
506
        t = NULL;
507

508
        for(int i = seq; i < waypointsEditable.count(); i++)
509
        {
pixhawk's avatar
pixhawk committed
510
            waypointsEditable[i]->setId(i);
511
        }
Alejandro's avatar
Alejandro committed
512

513
        emit waypointEditableListChanged();
514
        emit waypointEditableListChanged(uasid);
515 516 517 518 519
        return 0;
    }
    return -1;
}

520
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
521
{
522
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
523
    {
pixhawk's avatar
pixhawk committed
524
        Waypoint *t = waypointsEditable[cur_seq];
525
        if (cur_seq < new_seq) {
526 527
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
528
                waypointsEditable[i] = waypointsEditable[i+1];
529
                waypointsEditable[i]->setId(i);
530
            }
531 532 533 534 535
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
536
                waypointsEditable[i] = waypointsEditable[i-1];
537
                waypointsEditable[i]->setId(i);
538 539
            }
        }
pixhawk's avatar
pixhawk committed
540
        waypointsEditable[new_seq] = t;
541
        waypointsEditable[new_seq]->setId(new_seq);
542

543
        emit waypointEditableListChanged();
544
        emit waypointEditableListChanged(uasid);
545 546 547
    }
}

548
void UASWaypointManager::saveWaypoints(const QString &saveFile)
549 550 551 552 553 554
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
555 556

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

559
    for (int i = 0; i < waypointsEditable.count(); i++)
560
    {
pixhawk's avatar
pixhawk committed
561 562
        waypointsEditable[i]->setId(i);
        waypointsEditable[i]->save(out);
563 564 565 566
    }
    file.close();
}

567
void UASWaypointManager::loadWaypoints(const QString &loadFile)
568 569 570 571 572
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

573
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
574
        Waypoint *t = waypointsEditable[0];
575
        waypointsEditable.removeAt(0);
576 577 578 579
        delete t;
    }

    QTextStream in(&file);
580 581 582

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

583
    if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120"))
584
    {
585
        emit updateStatusString(tr("The waypoint file is not compatible with the current version of QGroundControl."));
586 587 588 589 590
    }
    else
    {
        while (!in.atEnd())
        {
591
            Waypoint *t = new Waypoint();
592 593
            if(t->load(in))
            {
594 595
                t->setId(waypointsEditable.count());
                waypointsEditable.insert(waypointsEditable.count(), t);
596 597 598
            }
            else
            {
599
                emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
600 601
                break;
            }
602 603
        }
    }
604

605 606
    file.close();

607
    emit loadWPFile();
608
    emit waypointEditableListChanged();
609
    emit waypointEditableListChanged(uasid);
610 611 612
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
613
{
614
    if (current_state == WP_IDLE)
615
    {
616
        emit _startProtocolTimer(); // Start timer on our thread
617
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
618

619 620
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
621
        current_partner_systemid = uasid;
lm's avatar
lm committed
622
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
623

624
        sendWaypointClearAll();
625 626 627
    }
}

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

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

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

676 677
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
678
    return waypointsEditable.indexOf(wp);
679 680
}

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

    return -1;
}

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

    return -1;
}

LM's avatar
LM committed
719 720
int UASWaypointManager::getNavTypeIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
721
    // Search through all waypointsEditable,
LM's avatar
LM committed
722 723
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
724
    foreach (Waypoint* p, waypointsEditable)
725 726 727 728 729
    {
        if (p->isNavigationType())
        {
            if (p == wp)
            {
LM's avatar
LM committed
730 731 732 733 734 735 736 737 738
                return i;
            }
            i++;
        }
    }

    return -1;
}

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

    return i;
}

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

    return i;
}

LM's avatar
LM committed
770 771
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
772
    // Search through all waypointsEditable,
LM's avatar
LM committed
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 778 779 780 781 782 783
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

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

    return i;
}

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

    return -1;
}

int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
822
    // Search through all waypointsEditable,
823 824
    // counting only those in mission frame
    int i = 0;
pixhawk's avatar
pixhawk committed
825
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
826
    {
827 828 829 830
        if (p->getFrame() == MAV_FRAME_MISSION)
        {
            if (p == wp)
            {
831 832 833 834 835 836 837 838 839
                return i;
            }
            i++;
        }
    }

    return -1;
}

pixhawk's avatar
pixhawk committed
840 841 842 843 844

/**
 * @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)
845
{
pixhawk's avatar
pixhawk committed
846
    read_to_edit = readToEdit;
847
    emit readGlobalWPFromUAS(true);
848
    if(current_state == WP_IDLE) {
849

850

851 852
        //Clear the old view-list before receiving the new one
        while(waypointsViewOnly.size()>0) {
853
            Waypoint *t = waypointsViewOnly[0];
854
            waypointsViewOnly.removeAt(0);
855
            delete t;
856
        }
857 858
        emit waypointViewOnlyListChanged();
        /* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
859 860
        //Clear the old edit-list before receiving the new one
        if (read_to_edit == true){
861
            while(waypointsEditable.count()>0) {
862 863 864
                Waypoint *t = waypointsEditable[0];
                waypointsEditable.remove(0);
                delete t;
865
            }
866
            emit waypointEditableListChanged();
867
        }
868
        */
869 870 871 872
        
        // We are signalling ourselves here so that the timer gets started on the right thread
        emit _startProtocolTimer();

873
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
874 875 876

        current_state = WP_GETLIST;
        current_wp_id = 0;
877
        current_partner_systemid = uasid;
lm's avatar
lm committed
878
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
879

880
        sendWaypointRequestList();
881

pixhawk's avatar
pixhawk committed
882 883
    }
}
884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917
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
918

919
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
920
{
921
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
922
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
923
        if (waypointsEditable.count() > 0) {
924
            emit _startProtocolTimer();  // Start timer on our thread
925
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
926

pixhawk's avatar
pixhawk committed
927
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
928 929
            current_state = WP_SENDLIST;
            current_wp_id = 0;
930
            current_partner_systemid = uasid;
lm's avatar
lm committed
931
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
932 933

            //clear local buffer
pixhawk's avatar
pixhawk committed
934 935 936
            // 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.
937
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
938 939 940
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
941

942 943
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
944
            //copy waypoint data to local buffer
945
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
946 947 948
                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
949
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
950 951

                cur_d->autocontinue = cur_s->getAutoContinue();
952
                cur_d->current = cur_s->getCurrent() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
953 954
                cur_d->param1 = cur_s->getParam1();
                cur_d->param2 = cur_s->getParam2();
lm's avatar
lm committed
955 956
                cur_d->param3 = cur_s->getParam3();
                cur_d->param4 = cur_s->getParam4();
957
                cur_d->frame = cur_s->getFrame();
lm's avatar
lm committed
958
                cur_d->command = cur_s->getAction();
959
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
pixhawk's avatar
pixhawk committed
960 961 962
                cur_d->x = cur_s->getX();
                cur_d->y = cur_s->getY();
                cur_d->z = cur_s->getZ();
963 964 965

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
966 967
                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
968
            }
969

970 971 972



pixhawk's avatar
pixhawk committed
973
            //send the waypoint count to UAS (this starts the send transaction)
974
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
975
        } else if (waypointsEditable.count() == 0)
976
        {
977
            clearWaypointList();
978
        }
Lorenz Meier's avatar
Lorenz Meier committed
979 980 981
    }
    else
    {
982 983
        // We're in another transaction, ignore command
        qDebug() << tr("UASWaypointManager::sendWaypoints() doing something else. Ignoring command");
984
    }
pixhawk's avatar
pixhawk committed
985 986
}

987 988
void UASWaypointManager::sendWaypointClearAll()
{
lm's avatar
lm committed
989
    if (!uas) return;
990

991 992 993
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
994
    mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
995
    uas->sendMessage(message);
996 997 998 999

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

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

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

1007 1008 1009
    // 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
1010
    mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
1011
    uas->sendMessage(message);
1012 1013 1014 1015

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

lm's avatar
lm committed
1016
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1017 1018 1019 1020
}

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
1021
    if (!uas) return;
1022 1023


1024 1025 1026
    // 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
1027
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1028
    uas->sendMessage(message);
1029 1030 1031 1032

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

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

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

1040 1041 1042 1043 1044
    // 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);
1045

1046
    // And update the UI.
1047 1048 1049
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1050

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

1054
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1055
{
lm's avatar
lm committed
1056
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1057

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

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

lm's avatar
lm committed
1067
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1068
}
pixhawk's avatar
pixhawk committed
1069

pixhawk's avatar
pixhawk committed
1070 1071
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1072
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1073
    mavlink_message_t message;
1074

1075
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1076

1077 1078
        // Fetch the current mission to send, and set it to apply to the curent UAS.
        mavlink_mission_item_t *wp = waypoint_buffer.at(seq);
1079
        wp->target_system = uasid;
lm's avatar
lm committed
1080
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1081

1082
        // Transmit the new mission
lm's avatar
lm committed
1083
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);
1084
        uas->sendMessage(message);
1085 1086 1087 1088

        // 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
1089
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1090
    }
pixhawk's avatar
pixhawk committed
1091
}
1092 1093 1094

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

1097 1098 1099
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
lm's avatar
lm committed
1100
    mavlink_msg_mission_ack_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpa);
1101
    uas->sendMessage(message);
1102

lm's avatar
lm committed
1103
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1104
}
1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129

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()
{
1130 1131
    if (waypointsEditable.count() > 0)
    {
1132 1133
        return waypointsEditable.last()->getAcceptanceRadius();
    }
1134 1135
    else
    {
1136 1137
        // Default to rotary wing waypoint radius for offline editing
        if (!uas || uas->isRotaryWing())
1138
        {
Thomas Gubler's avatar
Thomas Gubler committed
1139 1140 1141 1142 1143 1144
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
        else if (uas->isFixedWing())
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1145 1146 1147
    }

    return 10.0f;
1148 1149 1150 1151 1152 1153
}

float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
    return defaultAltitudeHomeOffset;
}
1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164


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

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