MockLinkMissionItemHandler.cc 12.6 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 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.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 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
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

#include "MockLinkMissionItemHandler.h"
25
#include "MockLink.h"
26 27 28

#include <QDebug>

29
QGC_LOGGING_CATEGORY(MockLinkMissionItemHandlerLog, "MockLinkMissionItemHandlerLog")
30

31
MockLinkMissionItemHandler::MockLinkMissionItemHandler(MockLink* mockLink, MAVLinkProtocol* mavlinkProtocol)
32 33 34
    : _mockLink(mockLink)
    , _missionItemResponseTimer(NULL)
    , _failureMode(FailNone)
35
    , _sendHomePositionOnEmptyList(false)
36
    , _mavlinkProtocol(mavlinkProtocol)
37
{
38
    Q_ASSERT(mockLink);
39 40
}

41 42 43 44 45 46 47 48 49 50 51 52 53 54
MockLinkMissionItemHandler::~MockLinkMissionItemHandler()
{

}

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

55
bool MockLinkMissionItemHandler::handleMessage(const mavlink_message_t& msg)
56 57 58
{
    switch (msg.msgid) {
        case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
59
            _handleMissionRequestList(msg);
60
            break;
61
            
62
        case MAVLINK_MSG_ID_MISSION_REQUEST:
63
            _handleMissionRequest(msg);
64
            break;
65 66 67 68 69
            
        case MAVLINK_MSG_ID_MISSION_ITEM:
            _handleMissionItem(msg);
            break;
            
70
        case MAVLINK_MSG_ID_MISSION_COUNT:
71
            _handleMissionCount(msg);
72
            break;
73 74 75 76 77 78 79
            
        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
80 81 82 83
            break;
    
        case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
            // Delete all mission items
84
            _missionItems.clear();
85
            break;
86 87 88
            
        default:
            return false;
89
    }
90 91
    
    return true;
92 93
}

94
void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message_t& msg)
95
{
96
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList read sequence";
97
    
98 99 100 101 102 103
    if (_failureMode != FailReadRequestListNoResponse) {
        mavlink_mission_request_list_t request;
        
        mavlink_msg_mission_request_list_decode(&msg, &request);
        
        Q_ASSERT(request.target_system == _mockLink->vehicleId());
104 105 106 107 108

        int itemCount = _missionItems.count();
        if (itemCount == 0 && _sendHomePositionOnEmptyList) {
            itemCount = 1;
        }
109 110 111 112 113 114 115 116
        
        mavlink_message_t   responseMsg;
        
        mavlink_msg_mission_count_pack(_mockLink->vehicleId(),
                                       MAV_COMP_ID_MISSIONPLANNER,
                                       &responseMsg,            // Outgoing message
                                       msg.sysid,               // Target is original sender
                                       msg.compid,              // Target is original sender
117
                                       itemCount);              // Number of mission items
118 119 120 121
        _mockLink->respondWithMavlinkMessage(responseMsg);
    } else {
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode";
    }
122
    
123 124 125
    if (_failureFirstTimeOnly) {
        _failureMode = FailNone;
    }
126
}
127

128
void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t& msg)
129
{
130
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest read sequence";
131
    
132
    mavlink_mission_request_t request;
133
    
134
    mavlink_msg_mission_request_decode(&msg, &request);
135
    
136 137
    Q_ASSERT(request.target_system == _mockLink->vehicleId());
    Q_ASSERT(request.seq < _missionItems.count());
138
    
139 140
    if ((_failureMode == FailReadRequest0NoResponse && request.seq == 0) ||
        (_failureMode == FailReadRequest1NoResponse && request.seq == 1)) {
141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode";
    } 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) ||
            (_failureMode == FailReadRequest1ErrorAck && request.seq == 1)) {
            _sendAck(MAV_MISSION_ERROR);
        } else {
            mavlink_message_t   responseMsg;
            
158 159 160 161 162 163 164 165 166 167
            mavlink_mission_item_t item;
            if (_missionItems.count() == 0 && _sendHomePositionOnEmptyList) {
                item.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
                item.command = MAV_CMD_NAV_WAYPOINT;
                item.current = false;
                item.autocontinue = true;
                item.param1 = item.param2 = item.param3 = item.param4 = item.x = item.y = item.z = 0;
            } else {
                item = _missionItems[request.seq];
            }
168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183
            
            mavlink_msg_mission_item_pack(_mockLink->vehicleId(),
                                          MAV_COMP_ID_MISSIONPLANNER,
                                          &responseMsg,            // Outgoing message
                                          msg.sysid,               // Target is original sender
                                          msg.compid,              // Target is original sender
                                          request.seq,             // Index of mission item being sent
                                          item.frame,
                                          item.command,
                                          item.current,
                                          item.autocontinue,
                                          item.param1, item.param2, item.param3, item.param4,
                                          item.x, item.y, item.z);
            _mockLink->respondWithMavlinkMessage(responseMsg);
        }
    }
184
    
185 186 187
    if (_failureFirstTimeOnly) {
        _failureMode = FailNone;
    }
188 189
}

190
void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t& msg)
191
{
192 193 194 195 196 197 198 199
    mavlink_mission_count_t missionCount;
    
    mavlink_msg_mission_count_decode(&msg, &missionCount);
    Q_ASSERT(missionCount.target_system == _mockLink->vehicleId());
    
    _writeSequenceCount = missionCount.count;
    Q_ASSERT(_writeSequenceCount >= 0);
    
200
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount write sequence _writeSequenceCount:" << _writeSequenceCount;
201 202 203 204
    
    _missionItems.clear();
    
    if (_writeSequenceCount == 0) {
205
        _sendAck(MAV_MISSION_ACCEPTED);
206
    } else {
207 208
        _writeSequenceIndex = 0;
        _requestNextMissionItem(_writeSequenceIndex);
209 210 211
    }
}

212
void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
213
{
214
    qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem write sequence sequenceNumber:" << sequenceNumber << "_failureMode:" << _failureMode;
215
    
216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237
    if ((_failureMode == FailWriteRequest0NoResponse && sequenceNumber == 0) ||
        (_failureMode == FailWriteRequest1NoResponse && sequenceNumber == 1)) {
        qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem not responding due to failure mode";
    } else {
        if (sequenceNumber >= _writeSequenceCount) {
            qCWarning(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount" << sequenceNumber << _writeSequenceCount;
            return;
        }
        
        if ((_failureMode == FailWriteRequest0IncorrectSequence && sequenceNumber == 0) ||
            (_failureMode == FailWriteRequest1IncorrectSequence && sequenceNumber == 1)) {
            sequenceNumber ++;
        }
        
        if ((_failureMode == FailWriteRequest0ErrorAck && sequenceNumber == 0) ||
            (_failureMode == FailWriteRequest1ErrorAck && sequenceNumber == 1)) {
            qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem sending ack error due to failure mode";
            _sendAck(MAV_MISSION_ERROR);
        } else {
            mavlink_message_t           message;
            mavlink_mission_request_t   missionRequest;
            
238 239
            missionRequest.target_system =      _mavlinkProtocol->getSystemId();
            missionRequest.target_component =   _mavlinkProtocol->getComponentId();
240 241 242 243 244 245 246 247
            missionRequest.seq =                sequenceNumber;
            
            mavlink_msg_mission_request_encode(_mockLink->vehicleId(), MAV_COMP_ID_MISSIONPLANNER, &message, &missionRequest);
            _mockLink->respondWithMavlinkMessage(message);

            // If response with Mission Item doesn't come before timer fires it's an error
            _startMissionItemResponseTimer();
        }
248
    }
249
    
250 251 252 253 254 255 256 257 258 259 260
    if (_failureFirstTimeOnly) {
        _failureMode = FailNone;
    }
}

void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
{
    qCDebug(MockLinkMissionItemHandlerLog) << "_sendAck write sequence complete ackType:" << ackType;
    
    mavlink_message_t       message;
    mavlink_mission_ack_t   missionAck;
261
    
262 263
    missionAck.target_system =      _mavlinkProtocol->getSystemId();
    missionAck.target_component =   _mavlinkProtocol->getComponentId();
264
    missionAck.type =               ackType;
265
    
266
    mavlink_msg_mission_ack_encode(_mockLink->vehicleId(), MAV_COMP_ID_MISSIONPLANNER, &message, &missionAck);
267
    _mockLink->respondWithMavlinkMessage(message);
268 269
}

270
void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg)
271
{
272 273
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionItem write sequence";
    
274 275
    _missionItemResponseTimer->stop();
    
276 277 278 279 280 281 282 283 284 285 286 287 288
    mavlink_mission_item_t missionItem;
    
    mavlink_msg_mission_item_decode(&msg, &missionItem);
    
    Q_ASSERT(missionItem.target_system == _mockLink->vehicleId());
    
    Q_ASSERT(!_missionItems.contains(missionItem.seq));
    Q_ASSERT(missionItem.seq == _writeSequenceIndex);
    
    _missionItems[missionItem.seq] = missionItem;
    
    _writeSequenceIndex++;
    if (_writeSequenceIndex < _writeSequenceCount) {
289 290 291 292 293 294
        if (_failureMode == FailWriteFinalAckMissingRequests && _writeSequenceIndex == 3) {
            // Send MAV_MISSION_ACCPETED ack too early
            _sendAck(MAV_MISSION_ACCEPTED);
        } else {
            _requestNextMissionItem(_writeSequenceIndex);
        }
295
    } else {
296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342
        if (_failureMode != FailWriteFinalAckNoResponse) {
            MAV_MISSION_RESULT ack = MAV_MISSION_ACCEPTED;
            
            if (_failureMode ==  FailWriteFinalAckErrorAck) {
                ack = MAV_MISSION_ERROR;
            }
            _sendAck(ack);
        }
    }
    if (_failureFirstTimeOnly) {
        _failureMode = FailNone;
    }
}

void MockLinkMissionItemHandler::_missionItemResponseTimeout(void)
{
    qWarning() << "Timeout waiting for next MISSION_ITEM";
    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);
}

void MockLinkMissionItemHandler::setMissionItemFailureMode(FailureMode_t failureMode, bool firstTimeOnly)
{
    _failureFirstTimeOnly = firstTimeOnly;
    _failureMode = failureMode;
}

void MockLinkMissionItemHandler::shutdown(void)
{
    if (_missionItemResponseTimer) {
        delete _missionItemResponseTimer;
343 344
    }
}