MockLinkMissionItemHandler.cc 16.5 KB
Newer Older
1 2
/****************************************************************************
 *
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10 11

#include "MockLinkMissionItemHandler.h"
Don Gagne's avatar
Don Gagne committed
12
#include "MockLink.h"
13 14 15

#include <QDebug>

Don Gagne's avatar
Don Gagne committed
16
QGC_LOGGING_CATEGORY(MockLinkMissionItemHandlerLog, "MockLinkMissionItemHandlerLog")
17

18
MockLinkMissionItemHandler::MockLinkMissionItemHandler(MockLink* mockLink, MAVLinkProtocol* mavlinkProtocol)
19 20 21 22 23 24 25 26
    : _mockLink                             (mockLink)
    , _missionItemResponseTimer             (nullptr)
    , _failureMode                          (FailNone)
    , _sendHomePositionOnEmptyList          (false)
    , _mavlinkProtocol                      (mavlinkProtocol)
    , _failReadRequestListFirstResponse     (true)
    , _failReadRequest1FirstResponse        (true)
    , _failWriteMissionCountFirstResponse   (true)
27
{
Don Gagne's avatar
Don Gagne committed
28
    Q_ASSERT(mockLink);
29 30
}

31 32 33 34 35 36 37 38 39 40 41 42 43 44
MockLinkMissionItemHandler::~MockLinkMissionItemHandler()
{

}

void MockLinkMissionItemHandler::_startMissionItemResponseTimer(void)
{
    if (!_missionItemResponseTimer) {
        _missionItemResponseTimer = new QTimer();
        connect(_missionItemResponseTimer, &QTimer::timeout, this, &MockLinkMissionItemHandler::_missionItemResponseTimeout);
    }
    _missionItemResponseTimer->start(500);
}

Don Gagne's avatar
Don Gagne committed
45
bool MockLinkMissionItemHandler::handleMessage(const mavlink_message_t& msg)
46 47
{
    switch (msg.msgid) {
48 49 50 51
    case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
        _handleMissionRequestList(msg);
        break;

52
    case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
53 54 55
        _handleMissionRequest(msg);
        break;

56
    case MAVLINK_MSG_ID_MISSION_ITEM_INT:
57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72
        _handleMissionItem(msg);
        break;

    case MAVLINK_MSG_ID_MISSION_COUNT:
        _handleMissionCount(msg);
        break;

    case MAVLINK_MSG_ID_MISSION_ACK:
        // Acks are received back for each MISSION_ITEM message
        break;

    case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
        // Sets the currently active mission item
        break;

    case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
73
        _handleMissionClearAll(msg);
74 75 76 77
        break;

    default:
        return false;
78
    }
Don Gagne's avatar
Don Gagne committed
79 80
    
    return true;
81 82
}

83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116
void MockLinkMissionItemHandler::_handleMissionClearAll(const mavlink_message_t& msg)
{

    mavlink_mission_clear_all_t clearAll;

    mavlink_msg_mission_clear_all_decode(&msg, &clearAll);

    Q_ASSERT(clearAll.target_system == _mockLink->vehicleId());

    _requestType = (MAV_MISSION_TYPE)clearAll.mission_type;
    qCDebug(MockLinkMissionItemHandlerLog) << QStringLiteral("_handleMissionClearAll %1").arg(_requestType);

    switch (_requestType) {
    case MAV_MISSION_TYPE_MISSION:
        _missionItems.clear();
        break;
    case MAV_MISSION_TYPE_FENCE:
        _fenceItems.clear();
        break;
    case MAV_MISSION_TYPE_RALLY:
        _rallyItems.clear();
        break;
    case MAV_MISSION_TYPE_ALL:
        _missionItems.clear();
        _fenceItems.clear();
        _rallyItems.clear();
        break;
    default:
        Q_ASSERT(false);
    }

    _sendAck(MAV_MISSION_ACCEPTED);
}

Don Gagne's avatar
Don Gagne committed
117
void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message_t& msg)
118
{
Don Gagne's avatar
Don Gagne committed
119
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList read sequence";
120
    
121 122 123 124 125 126 127 128
    _failReadRequest1FirstResponse = true;

    if (_failureMode == FailReadRequestListNoResponse) {
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode FailReadRequestListNoResponse";
    } else if (_failureMode == FailReadRequestListFirstResponse && _failReadRequestListFirstResponse) {
        _failReadRequestListFirstResponse = false;
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode FailReadRequestListFirstResponse";
    } else {
129 130
        mavlink_mission_request_list_t request;
        
131
        _failReadRequestListFirstResponse = true;
132 133 134
        mavlink_msg_mission_request_list_decode(&msg, &request);
        
        Q_ASSERT(request.target_system == _mockLink->vehicleId());
Don Gagne's avatar
Don Gagne committed
135

136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153
        _requestType = (MAV_MISSION_TYPE)request.mission_type;

        int itemCount;
        switch (_requestType) {
        case MAV_MISSION_TYPE_MISSION:
            itemCount = _missionItems.count();
            if (itemCount == 0 && _sendHomePositionOnEmptyList) {
                itemCount = 1;
            }
            break;
        case MAV_MISSION_TYPE_FENCE:
            itemCount = _fenceItems.count();
            break;
        case MAV_MISSION_TYPE_RALLY:
            itemCount = _rallyItems.count();
            break;
        default:
            Q_ASSERT(false);
Don Gagne's avatar
Don Gagne committed
154
        }
155 156 157
        
        mavlink_message_t   responseMsg;
        
158
        mavlink_msg_mission_count_pack_chan(_mockLink->vehicleId(),
159
                                            MAV_COMP_ID_AUTOPILOT1,
160
                                            _mockLink->mavlinkChannel(),
Donald Gagne's avatar
Donald Gagne committed
161 162 163 164
                                            &responseMsg,               // Outgoing message
                                            msg.sysid,                  // Target is original sender
                                            msg.compid,                 // Target is original sender
                                            itemCount,                  // Number of mission items
165
                                            _requestType);
166 167
        _mockLink->respondWithMavlinkMessage(responseMsg);
    }
Don Gagne's avatar
Don Gagne committed
168
}
169

Don Gagne's avatar
Don Gagne committed
170
void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t& msg)
171
{
Don Gagne's avatar
Don Gagne committed
172
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest read sequence";
173
    
174
    mavlink_mission_request_int_t request;
175
    
176
    mavlink_msg_mission_request_int_decode(&msg, &request);
177
    
Don Gagne's avatar
Don Gagne committed
178
    Q_ASSERT(request.target_system == _mockLink->vehicleId());
179

180 181 182 183 184 185 186
    if (_failureMode == FailReadRequest0NoResponse && request.seq == 0) {
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest0NoResponse";
    } else if (_failureMode == FailReadRequest1NoResponse && request.seq == 1) {
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest1NoResponse";
    } else if (_failureMode == FailReadRequest1FirstResponse && request.seq == 1 && _failReadRequest1FirstResponse) {
        _failReadRequest1FirstResponse = false;
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest1FirstResponse";
187 188 189 190 191 192 193 194 195 196 197
    } else {
        // FIXME: Track whether all items are requested, or requested in sequence
        
        if ((_failureMode == FailReadRequest0IncorrectSequence && request.seq == 0) ||
                (_failureMode == FailReadRequest1IncorrectSequence && request.seq == 1)) {
            // Send back the incorrect sequence number
            qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest sending bad sequence number";
            request.seq++;
        }
        
        if ((_failureMode == FailReadRequest0ErrorAck && request.seq == 0) ||
198
                (_failureMode == FailReadRequest1ErrorAck && request.seq == 1)) {
199
            _sendAck(_failureAckResult);
200
        } else {
201
            mavlink_mission_item_int_t missionItemInt;
202 203 204 205

            switch (request.mission_type) {
            case MAV_MISSION_TYPE_MISSION:
                if (_missionItems.count() == 0 && _sendHomePositionOnEmptyList) {
206 207 208 209
                    memset(&missionItemInt, 0, sizeof(missionItemInt));
                    missionItemInt.frame        = MAV_FRAME_GLOBAL_RELATIVE_ALT;
                    missionItemInt.command      = MAV_CMD_NAV_WAYPOINT;
                    missionItemInt.autocontinue = true;
210
                } else {
211
                    missionItemInt = _missionItems[request.seq];
212 213 214
                }
                break;
            case MAV_MISSION_TYPE_FENCE:
215
                missionItemInt = _fenceItems[request.seq];
216 217
                break;
            case MAV_MISSION_TYPE_RALLY:
218
                missionItemInt = _rallyItems[request.seq];
219 220 221
                break;
            default:
                Q_ASSERT(false);
Don Gagne's avatar
Don Gagne committed
222
            }
223
            
224 225 226 227 228 229 230 231 232 233 234 235 236 237 238
            mavlink_message_t responseMsg;
            mavlink_msg_mission_item_int_pack_chan(_mockLink->vehicleId(),
                                                   MAV_COMP_ID_AUTOPILOT1,
                                                   _mockLink->mavlinkChannel(),
                                                   &responseMsg,                // Outgoing message
                                                   msg.sysid,                   // Target is original sender
                                                   msg.compid,                  // Target is original sender
                                                   request.seq,                 // Index of mission item being sent
                                                   missionItemInt.frame,
                                                   missionItemInt.command,
                                                   missionItemInt.current,
                                                   missionItemInt.autocontinue,
                                                   missionItemInt.param1, missionItemInt.param2, missionItemInt.param3, missionItemInt.param4,
                                                   missionItemInt.x, missionItemInt.y, missionItemInt.z,
                                                   _requestType);
239 240 241
            _mockLink->respondWithMavlinkMessage(responseMsg);
        }
    }
242 243
}

Don Gagne's avatar
Don Gagne committed
244
void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t& msg)
245
{
Don Gagne's avatar
Don Gagne committed
246 247 248 249 250
    mavlink_mission_count_t missionCount;
    
    mavlink_msg_mission_count_decode(&msg, &missionCount);
    Q_ASSERT(missionCount.target_system == _mockLink->vehicleId());
    
251
    _requestType = (MAV_MISSION_TYPE)missionCount.mission_type;
Don Gagne's avatar
Don Gagne committed
252 253 254
    _writeSequenceCount = missionCount.count;
    Q_ASSERT(_writeSequenceCount >= 0);
    
255
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount write sequence _writeSequenceCount:" << _writeSequenceCount;
Don Gagne's avatar
Don Gagne committed
256
    
257 258 259 260 261 262 263 264 265 266 267
    switch (missionCount.mission_type) {
    case MAV_MISSION_TYPE_MISSION:
        _missionItems.clear();
        break;
    case MAV_MISSION_TYPE_FENCE:
        _fenceItems.clear();
        break;
    case MAV_MISSION_TYPE_RALLY:
        _rallyItems.clear();
        break;
    }
Don Gagne's avatar
Don Gagne committed
268 269
    
    if (_writeSequenceCount == 0) {
270
        _sendAck(MAV_MISSION_ACCEPTED);
271
    } else {
272 273 274 275 276 277 278 279 280 281
        if (_failureMode == FailWriteMissionCountNoResponse) {
            qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
            return;
        }
        if (_failureMode == FailWriteMissionCountFirstResponse && _failWriteMissionCountFirstResponse) {
            _failWriteMissionCountFirstResponse = false;
            qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
            return;
        }
        _failWriteMissionCountFirstResponse = true;
Don Gagne's avatar
Don Gagne committed
282 283
        _writeSequenceIndex = 0;
        _requestNextMissionItem(_writeSequenceIndex);
284 285 286
    }
}

Don Gagne's avatar
Don Gagne committed
287
void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
288
{
289
    qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem write sequence sequenceNumber:" << sequenceNumber << "_failureMode:" << _failureMode;
Don Gagne's avatar
Don Gagne committed
290
    
291 292
    if (_failureMode == FailWriteRequest1NoResponse && sequenceNumber == 1) {
        qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem not responding due to failure mode FailWriteRequest1NoResponse";
293 294 295 296 297 298 299
    } else {
        if (sequenceNumber >= _writeSequenceCount) {
            qCWarning(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount" << sequenceNumber << _writeSequenceCount;
            return;
        }
        
        if ((_failureMode == FailWriteRequest0IncorrectSequence && sequenceNumber == 0) ||
300
                (_failureMode == FailWriteRequest1IncorrectSequence && sequenceNumber == 1)) {
301 302 303 304
            sequenceNumber ++;
        }
        
        if ((_failureMode == FailWriteRequest0ErrorAck && sequenceNumber == 0) ||
305
                (_failureMode == FailWriteRequest1ErrorAck && sequenceNumber == 1)) {
306
            qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem sending ack error due to failure mode";
307
            _sendAck(_failureAckResult);
308
        } else {
309 310
            mavlink_message_t message;

311 312 313 314 315 316 317 318
            mavlink_msg_mission_request_int_pack_chan(_mockLink->vehicleId(),
                                                      MAV_COMP_ID_AUTOPILOT1,
                                                      _mockLink->mavlinkChannel(),
                                                      &message,
                                                      _mavlinkProtocol->getSystemId(),
                                                      _mavlinkProtocol->getComponentId(),
                                                      sequenceNumber,
                                                      _requestType);
319 320 321 322 323
            _mockLink->respondWithMavlinkMessage(message);

            // If response with Mission Item doesn't come before timer fires it's an error
            _startMissionItemResponseTimer();
        }
324
    }
325 326 327 328 329 330
}

void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
{
    qCDebug(MockLinkMissionItemHandlerLog) << "_sendAck write sequence complete ackType:" << ackType;
    
331
    mavlink_message_t message;
Don Gagne's avatar
Don Gagne committed
332
    
333
    mavlink_msg_mission_ack_pack_chan(_mockLink->vehicleId(),
334
                                      MAV_COMP_ID_AUTOPILOT1,
335 336 337 338 339 340
                                      _mockLink->mavlinkChannel(),
                                      &message,
                                      _mavlinkProtocol->getSystemId(),
                                      _mavlinkProtocol->getComponentId(),
                                      ackType,
                                      _requestType);
Don Gagne's avatar
Don Gagne committed
341
    _mockLink->respondWithMavlinkMessage(message);
342 343
}

Don Gagne's avatar
Don Gagne committed
344
void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg)
345
{
Don Gagne's avatar
Don Gagne committed
346 347
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionItem write sequence";
    
348 349
    _missionItemResponseTimer->stop();
    
350 351 352 353 354 355 356
    MAV_MISSION_TYPE            missionType;
    uint16_t                    seq;
    mavlink_mission_item_int_t  missionItemInt;

    mavlink_msg_mission_item_int_decode(&msg, &missionItemInt);
    missionType = static_cast<MAV_MISSION_TYPE>(missionItemInt.mission_type);
    seq = missionItemInt.seq;
Don Gagne's avatar
Don Gagne committed
357
    
358
    switch (missionType) {
359
    case MAV_MISSION_TYPE_MISSION:
360
        _missionItems[seq] = missionItemInt;
361 362
        break;
    case MAV_MISSION_TYPE_FENCE:
363
        _fenceItems[seq] = missionItemInt;
364 365
        break;
    case MAV_MISSION_TYPE_RALLY:
366 367 368 369 370
        _rallyItems[seq] = missionItemInt;
        break;
    case MAV_MISSION_TYPE_ENUM_END:
    case MAV_MISSION_TYPE_ALL:
        qWarning() << "Internal error";
371 372 373
        break;
    }

Don Gagne's avatar
Don Gagne committed
374 375
    _writeSequenceIndex++;
    if (_writeSequenceIndex < _writeSequenceCount) {
376
        if (_failureMode == FailWriteFinalAckMissingRequests && _writeSequenceIndex == 3) {
377
            // Send MAV_MISSION_ACCEPTED ack too early
378 379 380 381
            _sendAck(MAV_MISSION_ACCEPTED);
        } else {
            _requestNextMissionItem(_writeSequenceIndex);
        }
382
    } else {
383 384 385 386 387 388 389 390 391 392 393 394 395
        if (_failureMode != FailWriteFinalAckNoResponse) {
            MAV_MISSION_RESULT ack = MAV_MISSION_ACCEPTED;
            
            if (_failureMode ==  FailWriteFinalAckErrorAck) {
                ack = MAV_MISSION_ERROR;
            }
            _sendAck(ack);
        }
    }
}

void MockLinkMissionItemHandler::_missionItemResponseTimeout(void)
{
396
    qWarning() << "Timeout waiting for next MISSION_ITEM_INT";
397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416
    Q_ASSERT(false);
}

void MockLinkMissionItemHandler::sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType)
{
    _sendAck(ackType);
}

void MockLinkMissionItemHandler::sendUnexpectedMissionItem(void)
{
    // FIXME: NYI
    Q_ASSERT(false);
}

void MockLinkMissionItemHandler::sendUnexpectedMissionRequest(void)
{
    // FIXME: NYI
    Q_ASSERT(false);
}

417
void MockLinkMissionItemHandler::setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
418 419
{
    _failureMode = failureMode;
420
    _failureAckResult = failureAckResult;
421 422 423 424 425 426
}

void MockLinkMissionItemHandler::shutdown(void)
{
    if (_missionItemResponseTimer) {
        delete _missionItemResponseTimer;
427 428
    }
}