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

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

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

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

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

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

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

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

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

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

38
#define PROTOCOL_TIMEOUT_MS 2000    ///< maximum time to wait for pending messages until timeout
lm's avatar
lm committed
39 40
#define PROTOCOL_DELAY_MS 20        ///< minimum delay between sent messages
#define PROTOCOL_MAX_RETRIES 5      ///< maximum number of send retries (after timeout)
41
const float UASWaypointManager::defaultAltitudeHomeOffset   = 30.0f;
lm's avatar
lm committed
42
UASWaypointManager::UASWaypointManager(UAS* _uas)
43 44 45 46 47 48 49
    : uas(_uas),
      current_retries(0),
      current_wp_id(0),
      current_count(0),
      current_state(WP_IDLE),
      current_partner_systemid(0),
      current_partner_compid(0),
50 51
      currentWaypointEditable(NULL),
      protocol_timer(this)
pixhawk's avatar
pixhawk committed
52
{
53 54
    if (uas)
    {
lm's avatar
lm committed
55 56 57 58 59 60 61 62
        uasid = uas->getUASID();
        connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout()));
        connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64)));
        connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
    }
    else
    {
        uasid = 0;
63
    }
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 122 123
        double dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
        emit waypointDistanceChanged(dist);
    }
}

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

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

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

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


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

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

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

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

            //get next waypoint
            current_wp_id++;

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

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

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

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

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

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

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

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

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

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

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

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


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

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

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

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

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

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

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

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


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

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

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

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

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

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

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

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

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

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

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

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

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

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

    QTextStream out(&file);
540 541

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

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

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

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

    QTextStream in(&file);
565 566 567

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

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

590 591
    file.close();

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

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

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

609
        sendWaypointClearAll();
610 611 612
    }
}

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

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

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

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

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

    return -1;
}

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

    return -1;
}

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

    return -1;
}

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

    return i;
}

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

    return i;
}

LM's avatar
LM committed
755 756
int UASWaypointManager::getNavTypeCount()
{
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) {
LM's avatar
LM committed
761 762 763 764 765 766 767 768
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

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

    return i;
}

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

    return -1;
}

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

    return -1;
}

pixhawk's avatar
pixhawk committed
825 826 827 828 829

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

835

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

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

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

865
        sendWaypointRequestList();
866

pixhawk's avatar
pixhawk committed
867 868
    }
}
869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902
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
903

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

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

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

927 928
            bool noCurrent = true;

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

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

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

955 956 957



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

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

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

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

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

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

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

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

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

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


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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

lm's avatar
lm committed
1088
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1089
}
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

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

    return 10.0f;
1132 1133 1134 1135 1136 1137
}

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


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

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