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"
Don Gagne's avatar
Don Gagne committed
25
#include "MockLink.h"
26 27 28

#include <QDebug>

Don Gagne's avatar
Don Gagne committed
29
QGC_LOGGING_CATEGORY(MockLinkMissionItemHandlerLog, "MockLinkMissionItemHandlerLog")
30

Don Gagne's avatar
Don Gagne committed
31
MockLinkMissionItemHandler::MockLinkMissionItemHandler(MockLink* mockLink)
32 33 34
    : _mockLink(mockLink)
    , _missionItemResponseTimer(NULL)
    , _failureMode(FailNone)
Don Gagne's avatar
Don Gagne committed
35
    , _sendHomePositionOnEmptyList(false)
36
{
Don Gagne's avatar
Don Gagne committed
37
    Q_ASSERT(mockLink);
38 39
}

40 41 42 43 44 45 46 47 48 49 50 51 52 53
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
54
bool MockLinkMissionItemHandler::handleMessage(const mavlink_message_t& msg)
55 56 57
{
    switch (msg.msgid) {
        case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
Don Gagne's avatar
Don Gagne committed
58
            _handleMissionRequestList(msg);
59
            break;
Don Gagne's avatar
Don Gagne committed
60
            
61
        case MAVLINK_MSG_ID_MISSION_REQUEST:
Don Gagne's avatar
Don Gagne committed
62
            _handleMissionRequest(msg);
63
            break;
Don Gagne's avatar
Don Gagne committed
64 65 66 67 68
            
        case MAVLINK_MSG_ID_MISSION_ITEM:
            _handleMissionItem(msg);
            break;
            
69
        case MAVLINK_MSG_ID_MISSION_COUNT:
Don Gagne's avatar
Don Gagne committed
70
            _handleMissionCount(msg);
71
            break;
Don Gagne's avatar
Don Gagne committed
72 73 74 75 76 77 78
            
        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
79 80 81 82
            break;
    
        case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
            // Delete all mission items
Don Gagne's avatar
Don Gagne committed
83
            _missionItems.clear();
84
            break;
Don Gagne's avatar
Don Gagne committed
85 86 87
            
        default:
            return false;
88
    }
Don Gagne's avatar
Don Gagne committed
89 90
    
    return true;
91 92
}

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

        int itemCount = _missionItems.count();
        if (itemCount == 0 && _sendHomePositionOnEmptyList) {
            itemCount = 1;
        }
108 109 110 111 112 113 114 115
        
        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
Don Gagne's avatar
Don Gagne committed
116
                                       itemCount);              // Number of mission items
117 118 119 120
        _mockLink->respondWithMavlinkMessage(responseMsg);
    } else {
        qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode";
    }
121
    
122 123 124
    if (_failureFirstTimeOnly) {
        _failureMode = FailNone;
    }
Don Gagne's avatar
Don Gagne committed
125
}
126

Don Gagne's avatar
Don Gagne committed
127
void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t& msg)
128
{
Don Gagne's avatar
Don Gagne committed
129
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest read sequence";
130
    
Don Gagne's avatar
Don Gagne committed
131
    mavlink_mission_request_t request;
132
    
Don Gagne's avatar
Don Gagne committed
133
    mavlink_msg_mission_request_decode(&msg, &request);
134
    
Don Gagne's avatar
Don Gagne committed
135 136
    Q_ASSERT(request.target_system == _mockLink->vehicleId());
    Q_ASSERT(request.seq < _missionItems.count());
137
    
138 139
    if ((_failureMode == FailReadRequest0NoResponse && request.seq == 0) ||
        (_failureMode == FailReadRequest1NoResponse && request.seq == 1)) {
140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156
        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;
            
Don Gagne's avatar
Don Gagne committed
157 158 159 160 161 162 163 164 165 166
            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];
            }
167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182
            
            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);
        }
    }
183
    
184 185 186
    if (_failureFirstTimeOnly) {
        _failureMode = FailNone;
    }
187 188
}

Don Gagne's avatar
Don Gagne committed
189
void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t& msg)
190
{
Don Gagne's avatar
Don Gagne committed
191 192 193 194 195 196 197 198
    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);
    
199
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount write sequence _writeSequenceCount:" << _writeSequenceCount;
Don Gagne's avatar
Don Gagne committed
200 201 202 203
    
    _missionItems.clear();
    
    if (_writeSequenceCount == 0) {
204
        _sendAck(MAV_MISSION_ACCEPTED);
205
    } else {
Don Gagne's avatar
Don Gagne committed
206 207
        _writeSequenceIndex = 0;
        _requestNextMissionItem(_writeSequenceIndex);
208 209 210
    }
}

Don Gagne's avatar
Don Gagne committed
211
void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
212
{
213
    qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem write sequence sequenceNumber:" << sequenceNumber << "_failureMode:" << _failureMode;
Don Gagne's avatar
Don Gagne committed
214
    
215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246
    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;
            
            missionRequest.target_system =      MAVLinkProtocol::instance()->getSystemId();
            missionRequest.target_component =   MAVLinkProtocol::instance()->getComponentId();
            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();
        }
247
    }
Don Gagne's avatar
Don Gagne committed
248
    
249 250 251 252 253 254 255 256 257 258 259
    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;
Don Gagne's avatar
Don Gagne committed
260
    
261 262 263
    missionAck.target_system =      MAVLinkProtocol::instance()->getSystemId();
    missionAck.target_component =   MAVLinkProtocol::instance()->getComponentId();
    missionAck.type =               ackType;
Don Gagne's avatar
Don Gagne committed
264
    
265
    mavlink_msg_mission_ack_encode(_mockLink->vehicleId(), MAV_COMP_ID_MISSIONPLANNER, &message, &missionAck);
Don Gagne's avatar
Don Gagne committed
266
    _mockLink->respondWithMavlinkMessage(message);
267 268
}

Don Gagne's avatar
Don Gagne committed
269
void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg)
270
{
Don Gagne's avatar
Don Gagne committed
271 272
    qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionItem write sequence";
    
273 274
    _missionItemResponseTimer->stop();
    
Don Gagne's avatar
Don Gagne committed
275 276 277 278 279 280 281 282 283 284 285 286 287
    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) {
288 289 290 291 292 293
        if (_failureMode == FailWriteFinalAckMissingRequests && _writeSequenceIndex == 3) {
            // Send MAV_MISSION_ACCPETED ack too early
            _sendAck(MAV_MISSION_ACCEPTED);
        } else {
            _requestNextMissionItem(_writeSequenceIndex);
        }
294
    } else {
295 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
        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;
342 343
    }
}