UASWaypointManager.cc 39.4 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 "QGCMessageBox.h"
37

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

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

}

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

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

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

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

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

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

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

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

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


173
    } else {
174 175 176 177 178 179 180 181 182 183 184 185 186 187
		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);
		}
	}
188 189
}

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

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

Gus Grubba's avatar
Gus Grubba committed
198 199 200 201 202 203 204 205 206 207 208 209 210
            Waypoint *lwp_vo = new Waypoint(
                NULL,
                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);
pixhawk's avatar
pixhawk committed
211

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

            if (read_to_edit == true) {
Gus Grubba's avatar
Gus Grubba committed
215 216 217 218 219 220 221 222 223 224 225 226 227 228
                Waypoint *lwp_ed = new Waypoint(
                    NULL,
                    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);
pixhawk's avatar
pixhawk committed
229 230 231 232
                addWaypointEditable(lwp_ed, false);
                if (wp->current == 1) currentWaypointEditable = lwp_ed;
            }

pixhawk's avatar
pixhawk committed
233 234 235 236

            //get next waypoint
            current_wp_id++;

237
            if(current_wp_id < current_count) {
238
                sendWaypointRequest(current_wp_id);
239
            } else {
240 241
                sendWaypointAck(0);

pixhawk's avatar
pixhawk committed
242
                // all waypoints retrieved, change state to idle
pixhawk's avatar
pixhawk committed
243 244 245
                current_state = WP_IDLE;
                current_count = 0;
                current_wp_id = 0;
246

247
                emit _stopProtocolTimer(); // Stop timer on our thread
248
                emit readGlobalWPFromUAS(false);
249
                QTime time = QTime::currentTime();
250
                emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
251

pixhawk's avatar
pixhawk committed
252
            }
253
        } else {
254
            emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
255
        }
256 257 258 259
    } else if (systemId == current_partner_systemid
            && wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->getAction()) {
        // accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions
        // but only update view only side
Gus Grubba's avatar
Gus Grubba committed
260 261 262 263 264 265 266 267 268 269 270 271 272 273
        Waypoint *lwp_vo = new Waypoint(
            NULL,
            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);
274 275 276 277 278

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

279
    } else {
280
        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);
281
    }
pixhawk's avatar
pixhawk committed
282 283
}

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

lm's avatar
lm committed
348
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
349
{
350
    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)))) {
351
        emit _startProtocolTimer();  // Start timer on our thread
352
        current_retries = PROTOCOL_MAX_RETRIES;
353

354
        if (wpr->seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
355 356 357
            current_state = WP_SENDLIST_SENDWPS;
            current_wp_id = wpr->seq;
            sendWaypoint(current_wp_id);
358
        } else {
pixhawk's avatar
pixhawk committed
359 360
            //TODO: Error message or something
        }
361
    } else {
362
        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);
363
    }
364 365
}

lm's avatar
lm committed
366
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
367
{
368
	Q_UNUSED(compId);
lm's avatar
lm committed
369
    if (!uas) return;
370
    if (systemId == uasid) {
371
        emit updateStatusString(tr("Reached waypoint %1").arg(wpr->seq));
pixhawk's avatar
pixhawk committed
372
    }
pixhawk's avatar
pixhawk committed
373 374
}

lm's avatar
lm committed
375
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
pixhawk's avatar
pixhawk committed
376
{
377
    Q_UNUSED(compId);
lm's avatar
lm committed
378
    if (!uas) return;
379
    if (systemId == uasid) {
380
        // FIXME Petri
381
        if (current_state == WP_SETCURRENT) {
382
            emit _stopProtocolTimer();  // Stop timer on our thread
383
            current_state = WP_IDLE;
384 385

            // update the local main storage
pixhawk's avatar
pixhawk committed
386 387 388 389
            if (wpc->seq < waypointsViewOnly.size()) {
                for(int i = 0; i < waypointsViewOnly.size(); i++) {
                    if (waypointsViewOnly[i]->getId() == wpc->seq) {
                        waypointsViewOnly[i]->setCurrent(true);
390
                    } else {
pixhawk's avatar
pixhawk committed
391
                        waypointsViewOnly[i]->setCurrent(false);
392 393 394
                    }
                }
            }
395
        }
396
        emit updateStatusString(tr("New current waypoint %1").arg(wpc->seq));
397 398
        //emit update to UI widgets
        emit currentWaypointChanged(wpc->seq);
pixhawk's avatar
pixhawk committed
399
    }
pixhawk's avatar
pixhawk committed
400 401
}

402
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
403
{
404
    // If only one waypoint was changed, emit only WP signal
405
    if (wp != NULL) {
406
        emit waypointEditableChanged(uasid, wp);
407
    } else {
408
        emit waypointEditableListChanged();
409
        emit waypointEditableListChanged(uasid);
410
    }
411 412
}

413 414 415
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
    if (wp != NULL) {
416
        emit waypointViewOnlyChanged(uasid, wp);
417 418
    } else {
        emit waypointViewOnlyListChanged();
419
        emit waypointViewOnlyListChanged(uasid);
420 421
    }
}
422 423


424
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
pixhawk's avatar
pixhawk committed
425
{
pixhawk's avatar
pixhawk committed
426
    if (seq < waypointsViewOnly.size()) {
427
        if(current_state == WP_IDLE) {
428

429
            //send change to UAS - important to note: if the transmission fails, we have inconsistencies
430
            emit _startProtocolTimer();  // Start timer on our thread
431 432 433 434
            current_retries = PROTOCOL_MAX_RETRIES;

            current_state = WP_SETCURRENT;
            current_wp_id = seq;
435
            current_partner_systemid = uasid;
lm's avatar
lm committed
436
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
437 438 439 440 441 442 443 444 445

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

446 447
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
448
    if (seq < waypointsEditable.count()) {
449 450
        if(current_state == WP_IDLE) {
            //update local main storage
451
            for (int i = 0; i < waypointsEditable.count(); i++) {
452 453 454 455 456 457 458 459 460 461 462 463
                if (waypointsEditable[i]->getId() == seq) {
                    waypointsEditable[i]->setCurrent(true);
                } else {
                    waypointsEditable[i]->setCurrent(false);
                }
            }

            return 0;
        }
    }
    return -1;
}
pixhawk's avatar
pixhawk committed
464 465 466 467

void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
    if (wp)
468
    {
pixhawk's avatar
pixhawk committed
469 470 471 472
        waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));

        emit waypointViewOnlyListChanged();
473
        emit waypointViewOnlyListChanged(uasid);
pixhawk's avatar
pixhawk committed
474 475 476 477
    }
}


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

492 493
        wp->setId(waypointsEditable.count());
        if (enforceFirstActive && waypointsEditable.count() == 0)
494 495
        {
            wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
496
            currentWaypointEditable = wp;
497
        }
498
        waypointsEditable.insert(waypointsEditable.count(), wp);
499
        connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
500

501
        emit waypointEditableListChanged();
502
        emit waypointEditableListChanged(uasid);
503
    }
pixhawk's avatar
pixhawk committed
504 505
}

506 507 508 509 510
/**
 * @param enforceFirstActive Enforces that the first waypoint is set as active
 */
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
511
    // Check if this is the first waypoint in an offline list
512 513 514
    if (waypointsEditable.count() == 0 && uas == NULL) {
        QGCMessageBox::critical(tr("Waypoint Manager"),  _offlineEditingModeMessage);
    }
515

516
    Waypoint* wp = new Waypoint();
517 518 519
    wp->setId(waypointsEditable.count());
    wp->setFrame((MAV_FRAME)getFrameRecommendation());
    wp->setAltitude(getAltitudeRecommendation());
520
    wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
521
    if (enforceFirstActive && waypointsEditable.count() == 0)
522 523
    {
        wp->setCurrent(true);
pixhawk's avatar
pixhawk committed
524
        currentWaypointEditable = wp;
525
    }
526
    waypointsEditable.append(wp);
527
    connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
528

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

534
int UASWaypointManager::removeWaypoint(quint16 seq)
535
{
536
    if (seq < waypointsEditable.count())
537
    {
pixhawk's avatar
pixhawk committed
538
        Waypoint *t = waypointsEditable[seq];
539 540 541

        if (t->getCurrent() == true) //trying to remove the current waypoint
        {
542
            if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
543 544 545
            {
                waypointsEditable[seq+1]->setCurrent(true);
            }
546
            else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
547 548 549 550 551
            {
                waypointsEditable[seq-1]->setCurrent(true);
            }
        }

552
        waypointsEditable.removeAt(seq);
553
        delete t;
554
        t = NULL;
555

556
        for(int i = seq; i < waypointsEditable.count(); i++)
557
        {
pixhawk's avatar
pixhawk committed
558
            waypointsEditable[i]->setId(i);
559
        }
Alejandro's avatar
Alejandro committed
560

561
        emit waypointEditableListChanged();
562
        emit waypointEditableListChanged(uasid);
563 564 565 566 567
        return 0;
    }
    return -1;
}

568
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
569
{
570
    if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
571
    {
pixhawk's avatar
pixhawk committed
572
        Waypoint *t = waypointsEditable[cur_seq];
573
        if (cur_seq < new_seq) {
574 575
            for (int i = cur_seq; i < new_seq; i++)
            {
pixhawk's avatar
pixhawk committed
576
                waypointsEditable[i] = waypointsEditable[i+1];
577
                waypointsEditable[i]->setId(i);
578
            }
579 580 581 582 583
        }
        else
        {
            for (int i = cur_seq; i > new_seq; i--)
            {
pixhawk's avatar
pixhawk committed
584
                waypointsEditable[i] = waypointsEditable[i-1];
585
                waypointsEditable[i]->setId(i);
586 587
            }
        }
pixhawk's avatar
pixhawk committed
588
        waypointsEditable[new_seq] = t;
589
        waypointsEditable[new_seq]->setId(new_seq);
590

591
        emit waypointEditableListChanged();
592
        emit waypointEditableListChanged(uasid);
593 594 595
    }
}

596
void UASWaypointManager::saveWaypoints(const QString &saveFile)
597 598 599 600 601 602
{
    QFile file(saveFile);
    if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
        return;

    QTextStream out(&file);
603 604

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

607
    for (int i = 0; i < waypointsEditable.count(); i++)
608
    {
pixhawk's avatar
pixhawk committed
609 610
        waypointsEditable[i]->setId(i);
        waypointsEditable[i]->save(out);
611 612 613 614
    }
    file.close();
}

615
void UASWaypointManager::loadWaypoints(const QString &loadFile)
616 617 618 619 620
{
    QFile file(loadFile);
    if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
        return;

621
    while(waypointsEditable.count()>0) {
pixhawk's avatar
pixhawk committed
622
        Waypoint *t = waypointsEditable[0];
623
        waypointsEditable.removeAt(0);
624 625 626 627
        delete t;
    }

    QTextStream in(&file);
628 629 630

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

631
    if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120"))
632
    {
633
        emit updateStatusString(tr("The waypoint file is not compatible with the current version of QGroundControl."));
634 635 636 637 638
    }
    else
    {
        while (!in.atEnd())
        {
639
            Waypoint *t = new Waypoint();
640 641
            if(t->load(in))
            {
642 643 644 645 646
              //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
              //t->setId(waypointsEditable.count());
              // waypointsEditable.insert(waypointsEditable.count(), t);
              addWaypointEditable(t, false);
647 648 649
            }
            else
            {
650
                emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
651 652
                break;
            }
653 654
        }
    }
655

656 657
    file.close();

658
    emit loadWPFile();
659
    emit waypointEditableListChanged();
660
    emit waypointEditableListChanged(uasid);
661 662 663
}

void UASWaypointManager::clearWaypointList()
pixhawk's avatar
pixhawk committed
664
{
665
    if (current_state == WP_IDLE)
666
    {
667
        emit _startProtocolTimer(); // Start timer on our thread
668
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
669

670 671
        current_state = WP_CLEARLIST;
        current_wp_id = 0;
672
        current_partner_systemid = uasid;
lm's avatar
lm committed
673
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
674

675
        sendWaypointClearAll();
676 677 678
    }
}

679
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
680 681 682 683
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
684
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
685
    foreach (Waypoint* wp, waypointsEditable)
686 687 688
    {
        if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
689 690 691 692 693 694
            wps.append(wp);
        }
    }
    return wps;
}

695
const QList<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
lm's avatar
lm committed
696 697 698 699
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
700
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
701
    foreach (Waypoint* wp, waypointsEditable)
702 703 704
    {
        if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
        {
lm's avatar
lm committed
705 706 707 708 709 710
            wps.append(wp);
        }
    }
    return wps;
}

711
const QList<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
LM's avatar
LM committed
712 713 714 715
{
    // TODO Keep this global frame list up to date
    // with complete waypoint list
    // instead of filtering on each request
716
    QList<Waypoint*> wps;
pixhawk's avatar
pixhawk committed
717
    foreach (Waypoint* wp, waypointsEditable)
718 719 720
    {
        if (wp->isNavigationType())
        {
LM's avatar
LM committed
721 722 723 724 725 726
            wps.append(wp);
        }
    }
    return wps;
}

727 728
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
729
    return waypointsEditable.indexOf(wp);
730 731
}

732 733
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
734
    // Search through all waypointsEditable,
735 736
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
737
    foreach (Waypoint* p, waypointsEditable) {
738 739 740 741
        if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
            if (p == wp)
            {
742 743 744 745 746 747 748 749 750
                return i;
            }
            i++;
        }
    }

    return -1;
}

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

    return -1;
}

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

    return -1;
}

790 791
int UASWaypointManager::getGlobalFrameCount()
{
pixhawk's avatar
pixhawk committed
792
    // Search through all waypointsEditable,
793 794
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
795
    foreach (Waypoint* p, waypointsEditable)
796
    {
797 798
        if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
        {
799 800 801 802 803 804 805
            i++;
        }
    }

    return i;
}

lm's avatar
lm committed
806 807
int UASWaypointManager::getGlobalFrameAndNavTypeCount()
{
pixhawk's avatar
pixhawk committed
808
    // Search through all waypointsEditable,
lm's avatar
lm committed
809 810
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
811
    foreach (Waypoint* p, waypointsEditable) {
812
        if ((p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
813
        {
lm's avatar
lm committed
814 815 816 817 818 819 820
            i++;
        }
    }

    return i;
}

LM's avatar
LM committed
821 822
int UASWaypointManager::getNavTypeCount()
{
pixhawk's avatar
pixhawk committed
823
    // Search through all waypointsEditable,
LM's avatar
LM committed
824 825
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
826
    foreach (Waypoint* p, waypointsEditable) {
LM's avatar
LM committed
827 828 829 830 831 832 833 834
        if (p->isNavigationType()) {
            i++;
        }
    }

    return i;
}

835 836
int UASWaypointManager::getLocalFrameCount()
{
pixhawk's avatar
pixhawk committed
837
    // Search through all waypointsEditable,
838 839
    // counting only those in global frame
    int i = 0;
pixhawk's avatar
pixhawk committed
840
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
841
    {
842
        if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
lm's avatar
lm committed
843
        {
844 845 846 847 848 849 850 851 852
            i++;
        }
    }

    return i;
}

int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
853
    // Search through all waypointsEditable,
854 855
    // counting only those in local frame
    int i = 0;
pixhawk's avatar
pixhawk committed
856
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
857 858 859
    {
        if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
        {
860 861
            if (p == wp)
            {
862 863 864 865 866 867 868 869 870 871 872
                return i;
            }
            i++;
        }
    }

    return -1;
}

int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
{
pixhawk's avatar
pixhawk committed
873
    // Search through all waypointsEditable,
874 875
    // counting only those in mission frame
    int i = 0;
pixhawk's avatar
pixhawk committed
876
    foreach (Waypoint* p, waypointsEditable)
lm's avatar
lm committed
877
    {
878 879 880 881
        if (p->getFrame() == MAV_FRAME_MISSION)
        {
            if (p == wp)
            {
882 883 884 885 886 887 888 889 890
                return i;
            }
            i++;
        }
    }

    return -1;
}

pixhawk's avatar
pixhawk committed
891 892 893 894 895

/**
 * @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)
896
{
pixhawk's avatar
pixhawk committed
897
    read_to_edit = readToEdit;
898
    emit readGlobalWPFromUAS(true);
899
    if(current_state == WP_IDLE) {
900

901

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

924
        current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
925 926 927

        current_state = WP_GETLIST;
        current_wp_id = 0;
928
        current_partner_systemid = uasid;
lm's avatar
lm committed
929
        current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
930

931
        sendWaypointRequestList();
932

pixhawk's avatar
pixhawk committed
933 934
    }
}
935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968
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
969

970
void UASWaypointManager::writeWaypoints()
pixhawk's avatar
pixhawk committed
971
{
972
    if (current_state == WP_IDLE) {
pixhawk's avatar
pixhawk committed
973
        // Send clear all if count == 0
pixhawk's avatar
pixhawk committed
974
        if (waypointsEditable.count() > 0) {
975
            emit _startProtocolTimer();  // Start timer on our thread
976
            current_retries = PROTOCOL_MAX_RETRIES;
pixhawk's avatar
pixhawk committed
977

pixhawk's avatar
pixhawk committed
978
            current_count = waypointsEditable.count();
pixhawk's avatar
pixhawk committed
979 980
            current_state = WP_SENDLIST;
            current_wp_id = 0;
981
            current_partner_systemid = uasid;
lm's avatar
lm committed
982
            current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
983 984

            //clear local buffer
pixhawk's avatar
pixhawk committed
985 986 987
            // 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.
988
            while(!waypoint_buffer.empty()) {
pixhawk's avatar
pixhawk committed
989 990 991
                delete waypoint_buffer.back();
                waypoint_buffer.pop_back();
            }
pixhawk's avatar
pixhawk committed
992

993 994
            bool noCurrent = true;

pixhawk's avatar
pixhawk committed
995
            //copy waypoint data to local buffer
996
            for (int i=0; i < current_count; i++) {
lm's avatar
lm committed
997 998 999
                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
1000
                const Waypoint *cur_s = waypointsEditable.at(i);
pixhawk's avatar
pixhawk committed
1001 1002

                cur_d->autocontinue = cur_s->getAutoContinue();
1003
                cur_d->current = cur_s->getCurrent() & noCurrent;   //make sure only one current waypoint is selected, the first selected will be chosen
1004 1005
                cur_d->param1 = cur_s->getParam1();
                cur_d->param2 = cur_s->getParam2();
lm's avatar
lm committed
1006 1007
                cur_d->param3 = cur_s->getParam3();
                cur_d->param4 = cur_s->getParam4();
1008
                cur_d->frame = cur_s->getFrame();
lm's avatar
lm committed
1009
                cur_d->command = cur_s->getAction();
1010
                cur_d->seq = i;     // don't read out the sequence number of the waypoint class
pixhawk's avatar
pixhawk committed
1011 1012 1013
                cur_d->x = cur_s->getX();
                cur_d->y = cur_s->getY();
                cur_d->z = cur_s->getZ();
1014 1015 1016

                if (cur_s->getCurrent() && noCurrent)
                    noCurrent = false;
1017 1018
                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
1019
            }
1020

1021 1022 1023



pixhawk's avatar
pixhawk committed
1024
            //send the waypoint count to UAS (this starts the send transaction)
1025
            sendWaypointCount();
Lorenz Meier's avatar
Lorenz Meier committed
1026
        } else if (waypointsEditable.count() == 0)
1027
        {
1028
            clearWaypointList();
1029
        }
Lorenz Meier's avatar
Lorenz Meier committed
1030 1031 1032
    }
    else
    {
1033 1034
        // We're in another transaction, ignore command
        qDebug() << tr("UASWaypointManager::sendWaypoints() doing something else. Ignoring command");
1035
    }
pixhawk's avatar
pixhawk committed
1036 1037
}

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

1042 1043 1044
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
lm's avatar
lm committed
1045
    mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
1046
    uas->sendMessage(message);
1047 1048 1049 1050

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

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

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

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

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

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

void UASWaypointManager::sendWaypointCount()
{
lm's avatar
lm committed
1072
    if (!uas) return;
1073 1074


1075 1076 1077
    // 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
1078
    mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
1079
    uas->sendMessage(message);
1080 1081 1082 1083

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

lm's avatar
lm committed
1084
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1085 1086 1087 1088
}

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

1091 1092 1093 1094 1095
    // 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);
1096

1097
    // And update the UI.
1098 1099 1100
    QString statusMsg(tr("Requesting waypoint list..."));
    qDebug() << __FILE__ << __LINE__ << statusMsg;
    emit updateStatusString(statusMsg);
1101

lm's avatar
lm committed
1102
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1103 1104
}

1105
void UASWaypointManager::sendWaypointRequest(quint16 seq)
pixhawk's avatar
pixhawk committed
1106
{
lm's avatar
lm committed
1107
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1108

1109 1110 1111
    // 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
1112
    mavlink_msg_mission_request_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpr);
1113
    uas->sendMessage(message);
1114 1115 1116 1117

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

lm's avatar
lm committed
1118
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1119
}
pixhawk's avatar
pixhawk committed
1120

pixhawk's avatar
pixhawk committed
1121 1122
void UASWaypointManager::sendWaypoint(quint16 seq)
{
lm's avatar
lm committed
1123
    if (!uas) return;
pixhawk's avatar
pixhawk committed
1124
    mavlink_message_t message;
1125

1126
    if (seq < waypoint_buffer.count()) {
pixhawk's avatar
pixhawk committed
1127

1128 1129
        // Fetch the current mission to send, and set it to apply to the curent UAS.
        mavlink_mission_item_t *wp = waypoint_buffer.at(seq);
1130
        wp->target_system = uasid;
lm's avatar
lm committed
1131
        wp->target_component = MAV_COMP_ID_MISSIONPLANNER;
pixhawk's avatar
pixhawk committed
1132

1133
        // Transmit the new mission
lm's avatar
lm committed
1134
        mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, wp);
1135
        uas->sendMessage(message);
1136 1137 1138 1139

        // 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
1140
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
pixhawk's avatar
pixhawk committed
1141
    }
pixhawk's avatar
pixhawk committed
1142
}
1143 1144 1145

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

1148 1149 1150
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
lm's avatar
lm committed
1151
    mavlink_msg_mission_ack_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpa);
1152
    uas->sendMessage(message);
1153

lm's avatar
lm committed
1154
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1155
}
1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180

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()
{
1181 1182
    if (waypointsEditable.count() > 0)
    {
1183 1184
        return waypointsEditable.last()->getAcceptanceRadius();
    }
1185 1186
    else
    {
1187 1188
        // Default to rotary wing waypoint radius for offline editing
        if (!uas || uas->isRotaryWing())
1189
        {
Thomas Gubler's avatar
Thomas Gubler committed
1190 1191 1192 1193 1194 1195
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
        }
        else if (uas->isFixedWing())
        {
            return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
        }
1196 1197 1198
    }

    return 10.0f;
1199 1200 1201 1202 1203 1204
}

float UASWaypointManager::getHomeAltitudeOffsetDefault()
{
    return defaultAltitudeHomeOffset;
}
1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215


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

void UASWaypointManager::_stopProtocolTimerOnThisThread(void)
{
    protocol_timer.stop();
}
1216 1217 1218 1219


void UASWaypointManager::_updateWPonTimer()
{
1220 1221 1222 1223 1224
    while (current_state != WP_IDLE)
    {
        QGC::SLEEP::msleep(100);
    }
    readWaypoints(true);
1225
}