UASWaypointManager.cc 39.9 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);
117
    if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU))
118
    {
pixhawk's avatar
pixhawk committed
119 120 121
        double xdiff = x-currentWaypointEditable->getX();
        double ydiff = y-currentWaypointEditable->getY();
        double zdiff = z-currentWaypointEditable->getZ();
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);
135
    if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == 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
                Waypoint *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

Gus Grubba's avatar
Gus Grubba committed
199 200 201 202 203 204 205 206 207 208 209 210 211
            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
212

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

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

pixhawk's avatar
pixhawk committed
234 235 236 237

            //get next waypoint
            current_wp_id++;

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

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

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

pixhawk's avatar
pixhawk committed
253
            }
254
        } else {
255
            emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
pixhawk's avatar
pixhawk committed
256
        }
257 258 259 260
    } 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
261 262 263 264 265 266 267 268 269 270 271 272 273 274
        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);
275 276 277 278 279

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

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

lm's avatar
lm committed
285
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
286
{
287 288 289 290 291 292 293 294 295 296
    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) {
297
        if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
298
            //all waypoints sent and ack received
299
            emit _stopProtocolTimer();  // Stop timer on our thread
300
            current_state = WP_IDLE;
301 302 303
            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()));
304 305
        } else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
            //give up transmitting if a WP is rejected
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 336
            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;
337
            }
338
            emit _stopProtocolTimer();  // Stop timer on our thread
339
            current_state = WP_IDLE;
340
        } else if(current_state == WP_CLEARLIST) {
341
            emit _stopProtocolTimer(); // Stop timer on our thread
342
            current_state = WP_IDLE;
343 344
            QTime time = QTime::currentTime();
            emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString()));
345
        }
346 347 348
    }
}

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

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

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

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

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

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

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


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

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

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

            sendWaypointSetCurrent(current_wp_id);

            return 0;
        }
    }
    return -1;
}

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

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

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

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


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

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

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

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

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

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

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

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

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

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

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

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

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

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

    QTextStream out(&file);
604 605

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

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

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

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

    QTextStream in(&file);
629 630 631

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

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

657 658
    file.close();

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

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

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

676
        sendWaypointClearAll();
677 678 679
    }
}

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

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

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

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

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

    return -1;
}

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

    return -1;
}

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

    return -1;
}

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

    return i;
}

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

    return i;
}

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

    return i;
}

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

    return i;
}

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

    return -1;
}

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

    return -1;
}

pixhawk's avatar
pixhawk committed
892 893 894 895 896

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

902

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

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

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

932
        sendWaypointRequestList();
933

pixhawk's avatar
pixhawk committed
934 935
    }
}
936 937
bool UASWaypointManager::guidedModeSupported()
{
938
    return (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA);
939 940 941 942 943
}

void UASWaypointManager::goToWaypoint(Waypoint *wp)
{
    //Don't try to send a guided mode message to an AP that does not support it.
944
    if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964
    {
        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;
965 966
        mavlink_msg_mission_item_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &mission);
        _vehicle->sendMessage(message);
967 968 969
        QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
    }
}
pixhawk's avatar
pixhawk committed
970

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

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

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

994 995
            bool noCurrent = true;

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

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

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

1022 1023 1024



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

1039 1040
void UASWaypointManager::sendWaypointClearAll()
{
1041
    if (!_vehicle) return;
1042

1043 1044 1045
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_clear_all_t wpca = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
1046 1047
    mavlink_msg_mission_clear_all_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpca);
    _vehicle->sendMessage(message);
1048 1049 1050 1051

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

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

void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
{
1057
    if (!_vehicle) return;
1058

1059 1060 1061
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_set_current_t wpsc = {seq, (quint8)uasid, MAV_COMP_ID_MISSIONPLANNER};
1062 1063
    mavlink_msg_mission_set_current_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpsc);
    _vehicle->sendMessage(message);
1064 1065 1066 1067

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

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

void UASWaypointManager::sendWaypointCount()
{
1073
    if (!_vehicle) return;
1074 1075


1076 1077 1078
    // 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};
1079 1080
    mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpc);
    _vehicle->sendMessage(message);
1081 1082 1083 1084

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

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

void UASWaypointManager::sendWaypointRequestList()
{
1090
    if (!_vehicle) return;
1091

1092 1093 1094
    // 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};
1095 1096
    mavlink_msg_mission_request_list_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wprl);
    _vehicle->sendMessage(message);
1097

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

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

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

1110 1111 1112
    // 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};
1113 1114
    mavlink_msg_mission_request_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpr);
    _vehicle->sendMessage(message);
1115 1116 1117 1118

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

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

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

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

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

1134
        // Transmit the new mission
1135 1136
        mavlink_msg_mission_item_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, wp);
        _vehicle->sendMessage(message);
1137 1138 1139 1140

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

void UASWaypointManager::sendWaypointAck(quint8 type)
{
1147
    if (!_vehicle) return;
1148

1149 1150 1151
    // Send the message.
    mavlink_message_t message;
    mavlink_mission_ack_t wpa = {(quint8)uasid, MAV_COMP_ID_MISSIONPLANNER, type};
1152 1153
    mavlink_msg_mission_ack_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &wpa);
    _vehicle->sendMessage(message);
1154

lm's avatar
lm committed
1155
    QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
1156
}
1157 1158

UAS* UASWaypointManager::getUAS() {
1159
    return _vehicle ? _vehicle->uas() : NULL;    ///< Returns the owning UAS
1160 1161 1162 1163 1164 1165 1166
}

float UASWaypointManager::getAltitudeRecommendation()
{
    if (waypointsEditable.count() > 0) {
        return waypointsEditable.last()->getAltitude();
    } else {
1167
        return HomePositionManager::instance()->getHomeAltitude() + getHomeAltitudeOffsetDefault();
1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181
    }
}

int UASWaypointManager::getFrameRecommendation()
{
    if (waypointsEditable.count() > 0) {
        return static_cast<int>(waypointsEditable.last()->getFrame());
    } else {
        return MAV_FRAME_GLOBAL;
    }
}

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

    return 10.0f;
1200 1201 1202 1203 1204 1205
}

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


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

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


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