UASWaypointManager.cc 41 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 "HomePositionManager.h"
36
#include "QGCMessageBox.h"
37
#include "Vehicle.h"
38

39
#define PROTOCOL_TIMEOUT_MS 2000    ///< maximum time to wait for pending messages until timeout
lm's avatar
lm committed
40 41
#define PROTOCOL_DELAY_MS 20        ///< minimum delay between sent messages
#define PROTOCOL_MAX_RETRIES 5      ///< maximum number of send retries (after timeout)
42
const float UASWaypointManager::defaultAltitudeHomeOffset   = 30.0f;
43 44
UASWaypointManager::UASWaypointManager(Vehicle* vehicle, UAS* uas)
    : _vehicle(vehicle),
45 46 47 48 49 50
      current_retries(0),
      current_wp_id(0),
      current_count(0),
      current_state(WP_IDLE),
      current_partner_systemid(0),
      current_partner_compid(0),
51
      currentWaypointEditable(),
52 53
      protocol_timer(this),
	  _updateWPlist_timer(this)
pixhawk's avatar
pixhawk committed
54
{
55 56
    _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
    if (_vehicle)
58
    {
59
        uasid = _vehicle->id();
lm's avatar
lm committed
60 61
        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)));
72 73 74
	_updateWPlist_timer.setInterval(1500);
	_updateWPlist_timer.setSingleShot(true);
	connect(&_updateWPlist_timer, SIGNAL(timeout()), this, SLOT(_updateWPonTimer()));
pixhawk's avatar
pixhawk committed
75 76
}

LM's avatar
LM committed
77 78 79 80 81
UASWaypointManager::~UASWaypointManager()
{

}

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

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

105
        emit updateStatusString("Operation timed out.");
pixhawk's avatar
pixhawk committed
106

107 108 109 110
        current_state = WP_IDLE;
        current_count = 0;
        current_wp_id = 0;
    }
111 112
}

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

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

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

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

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


174
    } else {
175 176 177 178 179 180 181 182 183 184 185 186 187 188
		if (current_state != WP_GETLIST_GETWPS && systemId == current_partner_systemid)
		{
			qDebug("Requesting new waypoints. Propably changed onboard.");
			if (!_updateWPlist_timer.isActive())
			{
				current_state = WP_IDLE;
				_updateWPlist_timer.start();
			}
		}
		else
		{
			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);
		}
	}
189 190
}

lm's avatar
lm committed
191
void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp)
pixhawk's avatar
pixhawk committed
192
{
193
    if (systemId == current_partner_systemid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id) {
194
        emit _startProtocolTimer(); // Start timer on our thread
195 196
        current_retries = PROTOCOL_MAX_RETRIES;

197
        if(wp->seq == current_wp_id) {
pixhawk's avatar
pixhawk committed
198

Don Gagne's avatar
Don Gagne committed
199 200 201
            MissionItem *lwp_vo = new MissionItem(NULL,
                                                  wp->seq,
                                                  QGeoCoordinate(wp->x, wp->y, wp->z),
Don Gagne's avatar
Don Gagne committed
202
                                                  (MAV_CMD) wp->command,
Don Gagne's avatar
Don Gagne committed
203 204 205 206 207 208
                                                  wp->param1,
                                                  wp->param2,
                                                  wp->param3,
                                                  wp->param4,
                                                  wp->autocontinue,
                                                  wp->current,
Don Gagne's avatar
Don Gagne committed
209
                                                  (MAV_FRAME) wp->frame);
pixhawk's avatar
pixhawk committed
210

Gus Grubba's avatar
Gus Grubba committed
211
            addWaypointViewOnly(lwp_vo);
pixhawk's avatar
pixhawk committed
212 213

            if (read_to_edit == true) {
Don Gagne's avatar
Don Gagne committed
214 215 216
                MissionItem *lwp_ed = new MissionItem(NULL,
                                                      wp->seq,
                                                      QGeoCoordinate(wp->x, wp->y, wp->z),
Don Gagne's avatar
Don Gagne committed
217
                                                      (MAV_CMD) wp->command,
Don Gagne's avatar
Don Gagne committed
218 219 220 221 222 223
                                                      wp->param1,
                                                      wp->param2,
                                                      wp->param3,
                                                      wp->param4,
                                                      wp->autocontinue,
                                                      wp->current,
Don Gagne's avatar
Don Gagne committed
224
                                                      (MAV_FRAME) wp->frame);
pixhawk's avatar
pixhawk committed
225 226 227 228
                addWaypointEditable(lwp_ed, false);
                if (wp->current == 1) currentWaypointEditable = lwp_ed;
            }

pixhawk's avatar
pixhawk committed
229 230 231 232

            //get next waypoint
            current_wp_id++;

233
            if(current_wp_id < current_count) {
234
                sendWaypointRequest(current_wp_id);
235
            } else {
236 237
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
238
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
239 240 241
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
242

243
                emit _stopProtocolTimer(); // Stop timer on our thread
244
                emit readGlobalWPFromUAS(false);
245
                QTime time = QTime::currentTime();
246
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
247

pixhawk's avatar
pixhawk committed
248
            }
249
        } else {
250
            emit updateStatusString(tr("MissionItem ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
251
        }
252
    } else if (systemId == current_partner_systemid
Don Gagne's avatar
Don Gagne committed
253
            && wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->command()) {
254 255
        // accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions
        // but only update view only side
Don Gagne's avatar
Don Gagne committed
256 257 258
        MissionItem *lwp_vo = new MissionItem(NULL,
                                              wp->seq,
                                              QGeoCoordinate(wp->x, wp->y, wp->z),
Don Gagne's avatar
Don Gagne committed
259
                                              (MAV_CMD) wp->command,
Don Gagne's avatar
Don Gagne committed
260 261 262 263 264 265
                                              wp->param1,
                                              wp->param2,
                                              wp->param3,
                                              wp->param4,
                                              wp->autocontinue,
                                              wp->current,
Don Gagne's avatar
Don Gagne committed
266
                                              (MAV_FRAME) wp->frame);
267 268 269 270 271

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

272
    } else {
273
        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);
274
    }
pixhawk's avatar
pixhawk committed
275 276
}

lm's avatar
lm committed
277
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
278
{
279 280 281 282 283 284 285 286 287 288
    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) {
289
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
290
            //all waypoints sent and ack received
291
            emit _stopProtocolTimer();  // Stop timer on our thread
292
            current_state = WP_IDLE;
293 294 295
            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()));
296 297
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328
            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;
329
            }
330
            emit _stopProtocolTimer();  // Stop timer on our thread
331
            current_state = WP_IDLE;
332
        } else if(current_state == WP_CLEARLIST) {
333
            emit _stopProtocolTimer(); // Stop timer on our thread
334
            current_state = WP_IDLE;
335 336
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
337
        }
338 339 340
    }
}

lm's avatar
lm committed
341
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
342
{
343
    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)))) {
344
        emit _startProtocolTimer();  // Start timer on our thread
345
        current_retries = PROTOCOL_MAX_RETRIES;
346

347
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
348 349 350
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
351
        } else {
pixhawk's avatar
pixhawk committed
352 353
            //TODO: Error message or something
        }
354
    } else {
355
        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);
356
    }
357 358
}

lm's avatar
lm committed
359
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
360
{
361
	Q_UNUSED(compId);
362
    if (!_vehicle) return;
363
    if (systemId == uasid) {
364
        emit updateStatusString(tr("Reached waypoint %1").arg(wpr->seq));
pixhawk's avatar
pixhawk committed
365
    }
pixhawk's avatar
pixhawk committed
366 367
}

lm's avatar
lm committed
368
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
369
{
370
    Q_UNUSED(compId);
371
    if (!_vehicle) return;
372
    if (systemId == uasid) {
373
        // FIXME Petri
374
        if (current_state == WP_SETCURRENT) {
375
            emit _stopProtocolTimer();  // Stop timer on our thread
376
            current_state = WP_IDLE;
377 378

            // update the local main storage
pixhawk's avatar
pixhawk committed
379 380
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
Don Gagne's avatar
Don Gagne committed
381 382
                    if (waypointsViewOnly[i]->sequenceNumber() == wpc->seq) {
                        waypointsViewOnly[i]->setIsCurrentItem(true);
383
                    } else {
Don Gagne's avatar
Don Gagne committed
384
                        waypointsViewOnly[i]->setIsCurrentItem(false);
385 386 387
                    }
                }
            }
388
        }
389
        emit updateStatusString(tr("New current waypoint %1").arg(wpc->seq));
390 391
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
392
    }
pixhawk's avatar
pixhawk committed
393 394
}

395
void UASWaypointManager::notifyOfChangeEditable(MissionItem* wp)
396
{
397
    // If only one waypoint was changed, emit only WP signal
398
    if (wp != NULL) {
399
        emit waypointEditableChanged(uasid, wp);
400
    } else {
401
        emit waypointEditableListChanged();
402
        emit waypointEditableListChanged(uasid);
403
    }
404 405
}

406
void UASWaypointManager::notifyOfChangeViewOnly(MissionItem* wp)
407 408
{
    if (wp != NULL) {
409
        emit waypointViewOnlyChanged(uasid, wp);
410 411
    } else {
        emit waypointViewOnlyListChanged();
412
        emit waypointViewOnlyListChanged(uasid);
413 414
    }
}
415 416


417
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
418
{
pixhawk's avatar
pixhawk committed
419
    if (seq < waypointsViewOnly.size()) {
420
        if(current_state == WP_IDLE) {
421

422
            //send change to UAS - important to note: if the transmission fails, we have inconsistencies
423
            emit _startProtocolTimer();  // Start timer on our thread
424 425 426 427
            current_retries = PROTOCOL_MAX_RETRIES;

            current_state = WP_SETCURRENT;
            current_wp_id = seq;
428
            current_partner_systemid = uasid;
lm's avatar
lm committed
429
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
430 431 432 433 434 435 436 437 438

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

439 440
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
441
    if (seq < waypointsEditable.count()) {
442 443
        if(current_state == WP_IDLE) {
            //update local main storage
444
            for (int i = 0; i < waypointsEditable.count(); i++) {
Don Gagne's avatar
Don Gagne committed
445 446
                if (waypointsEditable[i]->sequenceNumber() == seq) {
                    waypointsEditable[i]->setIsCurrentItem(true);
447
                } else {
Don Gagne's avatar
Don Gagne committed
448
                    waypointsEditable[i]->setIsCurrentItem(false);
449 450 451 452 453 454 455 456
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
457

458
void UASWaypointManager::addWaypointViewOnly(MissionItem *wp)
pixhawk's avatar
pixhawk committed
459 460
{
    if (wp)
461
    {
pixhawk's avatar
pixhawk committed
462
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
463
        connect(wp, SIGNAL(changed(MissionItem*)), this, SLOT(notifyOfChangeViewOnly(MissionItem*)));
pixhawk's avatar
pixhawk committed
464 465

        emit waypointViewOnlyListChanged();
466
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
467 468 469 470
    }
}


pixhawk's avatar
pixhawk committed
471
/**
472
 * @warning Make sure the waypoint stays valid for the whole application lifecycle!
pixhawk's avatar
pixhawk committed
473
 * @param enforceFirstActive Enforces that the first waypoint is set as active
474
 * @see createWaypoint() is more suitable for most use cases
pixhawk's avatar
pixhawk committed
475
 */
476
void UASWaypointManager::addWaypointEditable(MissionItem *wp, bool enforceFirstActive)
477
{
lm's avatar
lm committed
478 479
    if (wp)
    {
480
        // Check if this is the first waypoint in an offline list
481
        if (waypointsEditable.count() == 0 && _vehicle == NULL) {
482
            QGCMessageBox::critical(tr("MissionItem Manager"),  _offlineEditingModeMessage);
483
        }
484

Don Gagne's avatar
Don Gagne committed
485
        wp->setSequenceNumber(waypointsEditable.count());
486
        if (enforceFirstActive && waypointsEditable.count() == 0)
487
        {
Don Gagne's avatar
Don Gagne committed
488
            wp->setIsCurrentItem(true);
pixhawk's avatar
pixhawk committed
489
            currentWaypointEditable = wp;
490
        }
491
        waypointsEditable.insert(waypointsEditable.count(), wp);
492
        connect(wp, SIGNAL(changed(MissionItem*)), this, SLOT(notifyOfChangeEditable(MissionItem*)));
493

494
        emit waypointEditableListChanged();
495
        emit waypointEditableListChanged(uasid);
496
    }
pixhawk's avatar
pixhawk committed
497 498
}

499 500 501
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
502
MissionItem* UASWaypointManager::createWaypoint(bool enforceFirstActive)
503
{
504
    // Check if this is the first waypoint in an offline list
505
    if (waypointsEditable.count() == 0 && _vehicle == NULL) {
506
        QGCMessageBox::critical(tr("MissionItem Manager"),  _offlineEditingModeMessage);
507
    }
508

509
    MissionItem* wp = new MissionItem();
Don Gagne's avatar
Don Gagne committed
510
    wp->setSequenceNumber(waypointsEditable.count());
511 512
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
513
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
514
    if (enforceFirstActive && waypointsEditable.count() == 0)
515
    {
Don Gagne's avatar
Don Gagne committed
516
        wp->setIsCurrentItem(true);
pixhawk's avatar
pixhawk committed
517
        currentWaypointEditable = wp;
518
    }
519
    waypointsEditable.append(wp);
520
    connect(wp, SIGNAL(changed(MissionItem*)), this, SLOT(notifyOfChangeEditable(MissionItem*)));
521

522
    emit waypointEditableListChanged();
523
    emit waypointEditableListChanged(uasid);
524 525 526
    return wp;
}

527
int UASWaypointManager::removeWaypoint(quint16 seq)
528
{
529
    if (seq < waypointsEditable.count())
530
    {
531
        MissionItem *t = waypointsEditable[seq];
532

Don Gagne's avatar
Don Gagne committed
533
        if (t->isCurrentItem() == true) //trying to remove the current waypoint
534
        {
535
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
536
            {
Don Gagne's avatar
Don Gagne committed
537
                waypointsEditable[seq+1]->setIsCurrentItem(true);
538
            }
539
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
540
            {
Don Gagne's avatar
Don Gagne committed
541
                waypointsEditable[seq-1]->setIsCurrentItem(true);
542 543 544
            }
        }

545
        waypointsEditable.removeAt(seq);
546
        delete t;
547
        t = NULL;
548

549
        for(int i = seq; i < waypointsEditable.count(); i++)
550
        {
Don Gagne's avatar
Don Gagne committed
551
            waypointsEditable[i]->setSequenceNumber(i);
552
        }
Alejandro's avatar
Alejandro committed
553

554
        emit waypointEditableListChanged();
555
        emit waypointEditableListChanged(uasid);
556 557 558 559 560
        return 0;
    }
    return -1;
}

561
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
562
{
563
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
564
    {
565
        MissionItem *t = waypointsEditable[cur_seq];
566
        if (cur_seq < new_seq) {
567 568
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
569
                waypointsEditable[i] = waypointsEditable[i+1];
Don Gagne's avatar
Don Gagne committed
570
                waypointsEditable[i]->setSequenceNumber(i);
571
            }
572 573 574 575 576
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
577
                waypointsEditable[i] = waypointsEditable[i-1];
Don Gagne's avatar
Don Gagne committed
578
                waypointsEditable[i]->setSequenceNumber(i);
579 580
            }
        }
pixhawk's avatar
pixhawk committed
581
        waypointsEditable[new_seq] = t;
Don Gagne's avatar
Don Gagne committed
582
        waypointsEditable[new_seq]->setSequenceNumber(new_seq);
583

584
        emit waypointEditableListChanged();
585
        emit waypointEditableListChanged(uasid);
586 587 588
    }
}

589
void UASWaypointManager::saveWaypoints(const QString &saveFile)
590 591 592 593 594 595
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
596 597

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

600
    for (int i = 0; i < waypointsEditable.count(); i++)
601
    {
Don Gagne's avatar
Don Gagne committed
602
        waypointsEditable[i]->setSequenceNumber(i);
pixhawk's avatar
pixhawk committed
603
        waypointsEditable[i]->save(out);
604 605 606 607
    }
    file.close();
}

608
void UASWaypointManager::loadWaypoints(const QString &loadFile)
609 610 611 612 613
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

614
    while(waypointsEditable.count()>0) {
615
        MissionItem *t = waypointsEditable[0];
616
        waypointsEditable.removeAt(0);
617 618 619 620
        delete t;
    }

    QTextStream in(&file);
621 622 623

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

624
    if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120"))
625
    {
626
        emit updateStatusString(tr("The waypoint file is not compatible with the current version of QGroundControl."));
627 628 629 630 631
    }
    else
    {
        while (!in.atEnd())
        {
632
            MissionItem *t = new MissionItem();
633 634
            if(t->load(in))
            {
635 636
              //Use the existing function to add waypoints to the map instead of doing it manually
              //Indeed, we should connect our waypoints to the map in order to synchronize them
Don Gagne's avatar
Don Gagne committed
637
              //t->setSequenceNumber(waypointsEditable.count());
638 639
              // waypointsEditable.insert(waypointsEditable.count(), t);
              addWaypointEditable(t, false);
640 641 642
            }
            else
            {
643
                emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
644 645
                break;
            }
646 647
        }
    }
648

649 650
    file.close();

651
    emit loadWPFile();
652
    emit waypointEditableListChanged();
653
    emit waypointEditableListChanged(uasid);
654 655 656
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
657
{
658
    if (current_state == WP_IDLE)
659
    {
660
        emit _startProtocolTimer(); // Start timer on our thread
661
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
662

663 664
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
665
        current_partner_systemid = uasid;
lm's avatar
lm committed
666
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
667

668
        sendWaypointClearAll();
669 670 671
    }
}

672
const QList<MissionItem *> UASWaypointManager::getGlobalFrameWaypointList()
673 674 675 676
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
677 678
    QList<MissionItem*> wps;
    foreach (MissionItem* wp, waypointsEditable)
679
    {
Don Gagne's avatar
Don Gagne committed
680
        if (wp->frame() == MAV_FRAME_GLOBAL || wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
681
        {
682 683 684 685 686 687
            wps.append(wp);
        }
    }
    return wps;
}

688
const QList<MissionItem *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
lm's avatar
lm committed
689 690 691 692
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
693 694
    QList<MissionItem*> wps;
    foreach (MissionItem* wp, waypointsEditable)
695
    {
Don Gagne's avatar
Don Gagne committed
696
        if ((wp->frame() == MAV_FRAME_GLOBAL || wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
697
        {
lm's avatar
lm committed
698 699 700 701 702 703
            wps.append(wp);
        }
    }
    return wps;
}

704
const QList<MissionItem *> UASWaypointManager::getNavTypeWaypointList()
LM's avatar
LM committed
705 706 707 708
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
709 710
    QList<MissionItem*> wps;
    foreach (MissionItem* wp, waypointsEditable)
711 712 713
    {
        if (wp->isNavigationType())
        {
LM's avatar
LM committed
714 715 716 717 718 719
            wps.append(wp);
        }
    }
    return wps;
}

720
int UASWaypointManager::getIndexOf(MissionItem* wp)
721
{
pixhawk's avatar
pixhawk committed
722
    return waypointsEditable.indexOf(wp);
723 724
}

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

    return -1;
}

744
int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(MissionItem* wp)
lm's avatar
lm committed
745
{
pixhawk's avatar
pixhawk committed
746
    // Search through all waypointsEditable,
lm's avatar
lm committed
747 748
    // counting only those in global frame
    int i = 0;
749
    foreach (MissionItem* p, waypointsEditable) {
Don Gagne's avatar
Don Gagne committed
750
        if ((p->frame() == MAV_FRAME_GLOBAL || wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
751 752 753
        {
            if (p == wp)
            {
lm's avatar
lm committed
754 755 756 757 758 759 760 761 762
                return i;
            }
            i++;
        }
    }

    return -1;
}

763
int UASWaypointManager::getNavTypeIndexOf(MissionItem* wp)
LM's avatar
LM committed
764
{
pixhawk's avatar
pixhawk committed
765
    // Search through all waypointsEditable,
LM's avatar
LM committed
766 767
    // counting only those in global frame
    int i = 0;
768
    foreach (MissionItem* p, waypointsEditable)
769 770 771 772 773
    {
        if (p->isNavigationType())
        {
            if (p == wp)
            {
LM's avatar
LM committed
774 775 776 777 778 779 780 781 782
                return i;
            }
            i++;
        }
    }

    return -1;
}

783 784
int UASWaypointManager::getGlobalFrameCount()
{
pixhawk's avatar
pixhawk committed
785
    // Search through all waypointsEditable,
786 787
    // counting only those in global frame
    int i = 0;
788
    foreach (MissionItem* p, waypointsEditable)
789
    {
Don Gagne's avatar
Don Gagne committed
790
        if (p->frame() == MAV_FRAME_GLOBAL || p->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
791
        {
792 793 794 795 796 797 798
            i++;
        }
    }

    return i;
}

lm's avatar
lm committed
799 800
int UASWaypointManager::getGlobalFrameAndNavTypeCount()
{
pixhawk's avatar
pixhawk committed
801
    // Search through all waypointsEditable,
lm's avatar
lm committed
802 803
    // counting only those in global frame
    int i = 0;
804
    foreach (MissionItem* p, waypointsEditable) {
Don Gagne's avatar
Don Gagne committed
805
        if ((p->frame() == MAV_FRAME_GLOBAL || p->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
806
        {
lm's avatar
lm committed
807 808 809 810 811 812 813
            i++;
        }
    }

    return i;
}

LM's avatar
LM committed
814 815
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
816
    // Search through all waypointsEditable,
LM's avatar
LM committed
817 818
    // counting only those in global frame
    int i = 0;
819
    foreach (MissionItem* p, waypointsEditable) {
LM's avatar
LM committed
820 821 822 823 824 825 826 827
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

828 829
int UASWaypointManager::getLocalFrameCount()
{
pixhawk's avatar
pixhawk committed
830
    // Search through all waypointsEditable,
831 832
    // counting only those in global frame
    int i = 0;
833
    foreach (MissionItem* p, waypointsEditable)
lm's avatar
lm committed
834
    {
Don Gagne's avatar
Don Gagne committed
835
        if (p->frame() == MAV_FRAME_LOCAL_NED || p->frame() == MAV_FRAME_LOCAL_ENU)
lm's avatar
lm committed
836
        {
837 838 839 840 841 842 843
            i++;
        }
    }

    return i;
}

844
int UASWaypointManager::getLocalFrameIndexOf(MissionItem* wp)
845
{
pixhawk's avatar
pixhawk committed
846
    // Search through all waypointsEditable,
847 848
    // counting only those in local frame
    int i = 0;
849
    foreach (MissionItem* p, waypointsEditable)
lm's avatar
lm committed
850
    {
Don Gagne's avatar
Don Gagne committed
851
        if (p->frame() == MAV_FRAME_LOCAL_NED || p->frame() == MAV_FRAME_LOCAL_ENU)
lm's avatar
lm committed
852
        {
853 854
            if (p == wp)
            {
855 856 857 858 859 860 861 862 863
                return i;
            }
            i++;
        }
    }

    return -1;
}

864
int UASWaypointManager::getMissionFrameIndexOf(MissionItem* wp)
865
{
pixhawk's avatar
pixhawk committed
866
    // Search through all waypointsEditable,
867 868
    // counting only those in mission frame
    int i = 0;
869
    foreach (MissionItem* p, waypointsEditable)
lm's avatar
lm committed
870
    {
Don Gagne's avatar
Don Gagne committed
871
        if (p->frame() == MAV_FRAME_MISSION)
872 873 874
        {
            if (p == wp)
            {
875 876 877 878 879 880 881 882 883
                return i;
            }
            i++;
        }
    }

    return -1;
}

pixhawk's avatar
pixhawk committed
884 885 886 887 888

/**
 * @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)
889
{
pixhawk's avatar
pixhawk committed
890
    read_to_edit = readToEdit;
891
    emit readGlobalWPFromUAS(true);
892
    if(current_state == WP_IDLE) {
893

894

895 896
        //Clear the old view-list before receiving the new one
        while(waypointsViewOnly.size()>0) {
897
            MissionItem *t = waypointsViewOnly[0];
898
            waypointsViewOnly.removeAt(0);
899
            delete t;
900
        }
901 902
        emit waypointViewOnlyListChanged();
        /* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
903 904
        //Clear the old edit-list before receiving the new one
        if (read_to_edit == true){
905
            while(waypointsEditable.count()>0) {
906
                MissionItem *t = waypointsEditable[0];
907 908
                waypointsEditable.remove(0);
                delete t;
909
            }
910
            emit waypointEditableListChanged();
911
        }
912
        */
913 914 915 916
        
        // We are signalling ourselves here so that the timer gets started on the right thread
        emit _startProtocolTimer();

917
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
918 919 920

        current_state = WP_GETLIST;
        current_wp_id = 0;
921
        current_partner_systemid = uasid;
lm's avatar
lm committed
922
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
923

924
        sendWaypointRequestList();
925

pixhawk's avatar
pixhawk committed
926 927
    }
}
928 929
bool UASWaypointManager::guidedModeSupported()
{
930
    return (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA);
931 932
}

933
void UASWaypointManager::goToWaypoint(MissionItem *wp)
934 935
{
    //Don't try to send a guided mode message to an AP that does not support it.
936
    if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
937 938 939
    {
        mavlink_mission_item_t mission;
        memset(&mission, 0, sizeof(mavlink_mission_item_t));   //initialize with zeros
940
        //const MissionItem *cur_s = waypointsEditable.at(i);
941 942 943

        mission.autocontinue = 0;
        mission.current = 2; //2 for guided mode
Don Gagne's avatar
Don Gagne committed
944 945 946 947 948 949
        mission.param1 = wp->param1();
        mission.param2 = wp->param2();
        mission.param3 = wp->param3();
        mission.param4 = wp->param4();
        mission.frame = wp->frame();
        mission.command = wp->command();
950
        mission.seq = 0;     // don't read out the sequence number of the waypoint class
Don Gagne's avatar
Don Gagne committed
951 952 953
        mission.x = wp->x();
        mission.y = wp->y();
        mission.z = wp->z();
954 955 956
        mavlink_message_t message;
        mission.target_system = uasid;
        mission.target_component = MAV_COMP_ID_MISSIONPLANNER;
957 958
        mavlink_msg_mission_item_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &mission);
        _vehicle->sendMessage(message);
959 960 961
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
    }
}
pixhawk's avatar
pixhawk committed
962

963
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
964
{
965
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
966
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
967
        if (waypointsEditable.count() > 0) {
968
            emit _startProtocolTimer();  // Start timer on our thread
969
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
970

pixhawk's avatar
pixhawk committed
971
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
972 973
            current_state = WP_SENDLIST;
            current_wp_id = 0;
974
            current_partner_systemid = uasid;
lm's avatar
lm committed
975
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
976 977

            //clear local buffer
pixhawk's avatar
pixhawk committed
978 979 980
            // 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.
981
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
982 983 984
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
985

986 987
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
988
            //copy waypoint data to local buffer
989
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
990 991 992
                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
993
                const MissionItem *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
994

Don Gagne's avatar
Don Gagne committed
995
                cur_d->autocontinue = cur_s->autoContinue();
Don Gagne's avatar
Don Gagne committed
996
                cur_d->current = cur_s->isCurrentItem() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
Don Gagne's avatar
Don Gagne committed
997 998 999 1000 1001 1002
                cur_d->param1 = cur_s->param1();
                cur_d->param2 = cur_s->param2();
                cur_d->param3 = cur_s->param3();
                cur_d->param4 = cur_s->param4();
                cur_d->frame = cur_s->frame();
                cur_d->command = cur_s->command();
1003
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
Don Gagne's avatar
Don Gagne committed
1004 1005 1006
                cur_d->x = cur_s->x();
                cur_d->y = cur_s->y();
                cur_d->z = cur_s->z();
1007

Don Gagne's avatar
Don Gagne committed
1008
                if (cur_s->isCurrentItem() && noCurrent)
1009
                    noCurrent = false;
1010 1011
                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
1012
            }
1013

1014 1015 1016



pixhawk's avatar
pixhawk committed
1017
            //send the waypoint count to UAS (this starts the send transaction)
1018
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
1019
        } else if (waypointsEditable.count() == 0)
1020
        {
1021
            clearWaypointList();
1022
        }
Lorenz Meier's avatar
Lorenz Meier committed
1023 1024 1025
    }
    else
    {
1026 1027
        // We're in another transaction, ignore command
        qDebug() << tr("UASWaypointManager::sendWaypoints() doing something else. Ignoring command");
1028
    }
pixhawk's avatar
pixhawk committed
1029 1030
}

1031 1032
void UASWaypointManager::sendWaypointClearAll()
{
1033
    if (!_vehicle) return;
1034

1035 1036 1037
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
1038 1039
    mavlink_msg_mission_clear_all_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpca);
    _vehicle->sendMessage(message);
1040 1041 1042 1043

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

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

void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
{
1049
    if (!_vehicle) return;
1050

1051 1052 1053
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_set_current_t wpsc = {seq, (quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
1054 1055
    mavlink_msg_mission_set_current_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpsc);
    _vehicle->sendMessage(message);
1056 1057 1058 1059

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

lm's avatar
lm committed
1060
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1061 1062 1063 1064
}

void UASWaypointManager::sendWaypointCount()
{
1065
    if (!_vehicle) return;
1066 1067


1068 1069 1070
    // 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};
1071 1072
    mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpc);
    _vehicle->sendMessage(message);
1073 1074 1075 1076

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

lm's avatar
lm committed
1077
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1078 1079 1080 1081
}

void UASWaypointManager::sendWaypointRequestList()
{
1082
    if (!_vehicle) return;
1083

1084 1085 1086
    // 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};
1087 1088
    mavlink_msg_mission_request_list_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wprl);
    _vehicle->sendMessage(message);
1089

1090
    // And update the UI.
1091 1092 1093
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1094

lm's avatar
lm committed
1095
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1096 1097
}

1098
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1099
{
1100
    if (!_vehicle) return;
pixhawk's avatar
pixhawk committed
1101

1102 1103 1104
    // 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};
1105 1106
    mavlink_msg_mission_request_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpr);
    _vehicle->sendMessage(message);
1107 1108 1109 1110

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

lm's avatar
lm committed
1111
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1112
}
pixhawk's avatar
pixhawk committed
1113

pixhawk's avatar
pixhawk committed
1114 1115
void UASWaypointManager::sendWaypoint(quint16 seq)
{
1116
    if (!_vehicle) return;
pixhawk's avatar
pixhawk committed
1117
    mavlink_message_t message;
1118

1119
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1120

1121 1122
        // Fetch the current mission to send, and set it to apply to the curent UAS.
        mavlink_mission_item_t *wp = waypoint_buffer.at(seq);
1123
        wp->target_system = uasid;
lm's avatar
lm committed
1124
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1125

1126
        // Transmit the new mission
1127 1128
        mavlink_msg_mission_item_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, wp);
        _vehicle->sendMessage(message);
1129 1130 1131 1132

        // 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
1133
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1134
    }
pixhawk's avatar
pixhawk committed
1135
}
1136 1137 1138

void UASWaypointManager::sendWaypointAck(quint8 type)
{
1139
    if (!_vehicle) return;
1140

1141 1142 1143
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
1144 1145
    mavlink_msg_mission_ack_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpa);
    _vehicle->sendMessage(message);
1146

lm's avatar
lm committed
1147
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1148
}
1149 1150

UAS* UASWaypointManager::getUAS() {
1151
    return _vehicle ? _vehicle->uas() : NULL;    ///< Returns the owning UAS
1152 1153 1154 1155 1156
}

float UASWaypointManager::getAltitudeRecommendation()
{
    if (waypointsEditable.count() > 0) {
Don Gagne's avatar
Don Gagne committed
1157
        return waypointsEditable.last()->altitude();
1158
    } else {
1159
        return HomePositionManager::instance()->getHomeAltitude() + getHomeAltitudeOffsetDefault();
1160 1161 1162 1163 1164 1165
    }
}

int UASWaypointManager::getFrameRecommendation()
{
    if (waypointsEditable.count() > 0) {
Don Gagne's avatar
Don Gagne committed
1166
        return static_cast<int>(waypointsEditable.last()->frame());
1167 1168 1169 1170 1171 1172 1173
    } else {
        return MAV_FRAME_GLOBAL;
    }
}

float UASWaypointManager::getAcceptanceRadiusRecommendation()
{
1174 1175
    if (waypointsEditable.count() > 0)
    {
Don Gagne's avatar
Don Gagne committed
1176
        return waypointsEditable.last()->acceptanceRadius();
1177
    }
1178 1179
    else
    {
1180
        // Default to rotary wing waypoint radius for offline editing
1181
        if (!_vehicle || _vehicle->uas()->isRotaryWing())
1182
        {
Thomas Gubler's avatar
Thomas Gubler committed
1183 1184
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
1185
        else if (_vehicle->uas()->isFixedWing())
Thomas Gubler's avatar
Thomas Gubler committed
1186 1187 1188
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1189 1190 1191
    }

    return 10.0f;
1192 1193 1194 1195 1196 1197
}

float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
    return defaultAltitudeHomeOffset;
}
1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208


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

void UASWaypointManager::_stopProtocolTimerOnThisThread(void)
{
    protocol_timer.stop();
}
1209 1210 1211 1212


void UASWaypointManager::_updateWPonTimer()
{
1213 1214 1215 1216 1217
    while (current_state != WP_IDLE)
    {
        QGC::SLEEP::msleep(100);
    }
    readWaypoints(true);
1218
}