Commit b05575fa authored by Don Gagne's avatar Don Gagne

MissionManagerTest protocol hardening tests

- Fixed bugs found to unit test
parent e352f247
This diff is collapsed.
...@@ -67,12 +67,24 @@ public: ...@@ -67,12 +67,24 @@ public:
/// Returns a copy of the current set of mission items. Caller is responsible for /// Returns a copy of the current set of mission items. Caller is responsible for
/// freeing returned object. /// freeing returned object.
QmlObjectListModel* copyMissionItems(void); QmlObjectListModel* copyMissionItems(void);
/// Error codes returned in error signal
typedef enum {
InternalError,
AckTimeoutError, ///< Timed out waiting for response from vehicle
ProtocolOrderError, ///< Incorrect protocol sequence from vehicle
RequestRangeError, ///< Vehicle requested item out of range
ItemMismatchError, ///< Vehicle returned item with seq # different than requested
VehicleError, ///< Vehicle returned error
MissingRequestsError, ///< Vehicle did not request all items during write sequence
} ErrorCode_t;
signals: signals:
// Public signals // Public signals
void canEditChanged(bool canEdit); void canEditChanged(bool canEdit);
void newMissionItemsAvailable(void); void newMissionItemsAvailable(void);
void inProgressChanged(bool inProgress); void inProgressChanged(bool inProgress);
void error(int errorCode, const QString& errorMsg);
private slots: private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message); void _mavlinkMessageReceived(const mavlink_message_t& message);
...@@ -86,7 +98,7 @@ private: ...@@ -86,7 +98,7 @@ private:
AckMissionRequest, ///< MISSION_REQUEST is expected, or MISSION_ACK to end sequence AckMissionRequest, ///< MISSION_REQUEST is expected, or MISSION_ACK to end sequence
} AckType_t; } AckType_t;
void _startAckTimeout(AckType_t ack, const mavlink_message_t& message); void _startAckTimeout(AckType_t ack);
bool _stopAckTimeout(AckType_t expectedAck); bool _stopAckTimeout(AckType_t expectedAck);
void _sendTransactionComplete(void); void _sendTransactionComplete(void);
void _handleMissionCount(const mavlink_message_t& message); void _handleMissionCount(const mavlink_message_t& message);
...@@ -95,6 +107,10 @@ private: ...@@ -95,6 +107,10 @@ private:
void _handleMissionAck(const mavlink_message_t& message); void _handleMissionAck(const mavlink_message_t& message);
void _requestNextMissionItem(int sequenceNumber); void _requestNextMissionItem(int sequenceNumber);
void _clearMissionItems(void); void _clearMissionItems(void);
void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
void _retryWrite(void);
void _retryRead(void);
bool _retrySequence(AckType_t ackType);
private: private:
Vehicle* _vehicle; Vehicle* _vehicle;
...@@ -104,7 +120,6 @@ private: ...@@ -104,7 +120,6 @@ private:
QTimer* _ackTimeoutTimer; QTimer* _ackTimeoutTimer;
AckType_t _retryAck; AckType_t _retryAck;
mavlink_message_t _retryMessage;
int _retryCount; int _retryCount;
int _expectedSequenceNumber; int _expectedSequenceNumber;
...@@ -113,7 +128,7 @@ private: ...@@ -113,7 +128,7 @@ private:
QmlObjectListModel _missionItems; QmlObjectListModel _missionItems;
static const int _ackTimeoutMilliseconds= 1000; static const int _ackTimeoutMilliseconds= 500;
static const int _maxRetryCount = 5; static const int _maxRetryCount = 5;
}; };
......
This diff is collapsed.
...@@ -42,9 +42,11 @@ private slots: ...@@ -42,9 +42,11 @@ private slots:
void _readEmptyVehicle(void); void _readEmptyVehicle(void);
void _roundTripItems(void); void _roundTripItems(void);
void _testWriteFailureHandling(void);
private: private:
void _checkInProgressValues(bool inProgress); void _checkInProgressValues(bool inProgress);
void _writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MissionManager::ErrorCode_t errorCode, bool failFirstTimeOnly);
MockLink* _mockLink; MockLink* _mockLink;
MissionManager* _missionManager; MissionManager* _missionManager;
...@@ -53,6 +55,7 @@ private: ...@@ -53,6 +55,7 @@ private:
canEditChangedSignalIndex = 0, canEditChangedSignalIndex = 0,
newMissionItemsAvailableSignalIndex, newMissionItemsAvailableSignalIndex,
inProgressChangedSignalIndex, inProgressChangedSignalIndex,
errorSignalIndex,
maxSignalIndex maxSignalIndex
}; };
...@@ -60,6 +63,7 @@ private: ...@@ -60,6 +63,7 @@ private:
canEditChangedSignalMask = 1 << canEditChangedSignalIndex, canEditChangedSignalMask = 1 << canEditChangedSignalIndex,
newMissionItemsAvailableSignalMask = 1 << newMissionItemsAvailableSignalIndex, newMissionItemsAvailableSignalMask = 1 << newMissionItemsAvailableSignalIndex,
inProgressChangedSignalMask = 1 << inProgressChangedSignalIndex, inProgressChangedSignalMask = 1 << inProgressChangedSignalIndex,
errorSignalMask = 1 << errorSignalIndex,
}; };
MultiSignalSpy* _multiSpy; MultiSignalSpy* _multiSpy;
......
...@@ -85,6 +85,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -85,6 +85,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
, _satelliteLock(0) , _satelliteLock(0)
, _wpm(NULL) , _wpm(NULL)
, _updateCount(0) , _updateCount(0)
, _missionManager(NULL)
, _armed(false) , _armed(false)
, _base_mode(0) , _base_mode(0)
, _custom_mode(0) , _custom_mode(0)
...@@ -164,6 +165,9 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -164,6 +165,9 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
Vehicle::~Vehicle() Vehicle::~Vehicle()
{ {
delete _missionManager;
_missionManager = NULL;
// Stop listening for system messages // Stop listening for system messages
disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage); disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
// Disconnect any previously connected active MAV // Disconnect any previously connected active MAV
......
...@@ -66,17 +66,18 @@ union px4_custom_mode { ...@@ -66,17 +66,18 @@ union px4_custom_mode {
float data_float; float data_float;
}; };
MockLink::MockLink(MockConfiguration* config) : MockLink::MockLink(MockConfiguration* config)
_name("MockLink"), : _missionItemHandler(this)
_connected(false), , _name("MockLink")
_vehicleSystemId(128), // FIXME: Pull from eventual parameter manager , _connected(false)
_vehicleComponentId(200), // FIXME: magic number? , _vehicleSystemId(128) // FIXME: Pull from eventual parameter manager
_inNSH(false), , _vehicleComponentId(200) // FIXME: magic number?
_mavlinkStarted(false), , _inNSH(false)
_mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED), , _mavlinkStarted(false)
_mavState(MAV_STATE_STANDBY), , _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
_autopilotType(MAV_AUTOPILOT_PX4), , _mavState(MAV_STATE_STANDBY)
_fileServer(NULL) , _autopilotType(MAV_AUTOPILOT_PX4)
, _fileServer(NULL)
{ {
_config = config; _config = config;
union px4_custom_mode px4_cm; union px4_custom_mode px4_cm;
...@@ -88,10 +89,8 @@ MockLink::MockLink(MockConfiguration* config) : ...@@ -88,10 +89,8 @@ MockLink::MockLink(MockConfiguration* config) :
_fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this); _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
Q_CHECK_PTR(_fileServer); Q_CHECK_PTR(_fileServer);
_missionItemHandler = new MockLinkMissionItemHandler(this);
Q_CHECK_PTR(_missionItemHandler);
moveToThread(this); moveToThread(this);
_loadParams(); _loadParams();
QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes); QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
} }
...@@ -149,6 +148,8 @@ void MockLink::run(void) ...@@ -149,6 +148,8 @@ void MockLink::run(void)
QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks); QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks); QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks); QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
_missionItemHandler.shutdown();
} }
void MockLink::_run1HzTasks(void) void MockLink::_run1HzTasks(void)
...@@ -303,8 +304,7 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes) ...@@ -303,8 +304,7 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
continue; continue;
} }
Q_ASSERT(_missionItemHandler); if (_missionItemHandler.handleMessage(msg)) {
if (_missionItemHandler->handleMessage(msg)) {
continue; continue;
} }
...@@ -668,3 +668,7 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) ...@@ -668,3 +668,7 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg)
} }
} }
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
_missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
...@@ -85,6 +85,23 @@ public: ...@@ -85,6 +85,23 @@ public:
bool disconnect(void); bool disconnect(void);
LinkConfiguration* getLinkConfiguration() { return _config; } LinkConfiguration* getLinkConfiguration() { return _config; }
/// Sets a failure mode for unit testing
/// @param failureMode Type of failure to simulate
/// @param firstTimeOnly true: fail first call, success subsequent calls, false: fail all calls
void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly);
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType) { _missionItemHandler.sendUnexpectedMissionAck(ackType); }
/// Called to send a MISSION_ITEM message while the MissionManager is in idle state
void sendUnexpectedMissionItem(void) { _missionItemHandler.sendUnexpectedMissionItem(); }
/// Called to send a MISSION_REQUEST message while the MissionManager is in idle state
void sendUnexpectedMissionRequest(void) { _missionItemHandler.sendUnexpectedMissionRequest(); }
/// Reset the state of the MissionItemHandler to no items, no transactions in progress.
void resetMissionItemHandler(void) { _missionItemHandler.reset(); }
signals: signals:
/// @brief Used internally to move data to the thread. /// @brief Used internally to move data to the thread.
...@@ -126,7 +143,7 @@ private: ...@@ -126,7 +143,7 @@ private:
float _floatUnionForParam(int componentId, const QString& paramName); float _floatUnionForParam(int componentId, const QString& paramName);
void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat); void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat);
MockLinkMissionItemHandler* _missionItemHandler; MockLinkMissionItemHandler _missionItemHandler;
QString _name; QString _name;
bool _connected; bool _connected;
......
This diff is collapsed.
...@@ -26,6 +26,7 @@ ...@@ -26,6 +26,7 @@
#include <QObject> #include <QObject>
#include <QMap> #include <QMap>
#include <QTimer>
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
...@@ -40,11 +41,55 @@ class MockLinkMissionItemHandler : public QObject ...@@ -40,11 +41,55 @@ class MockLinkMissionItemHandler : public QObject
public: public:
MockLinkMissionItemHandler(MockLink* mockLink); MockLinkMissionItemHandler(MockLink* mockLink);
~MockLinkMissionItemHandler();
// Prepares for destruction on correct thread
void shutdown(void);
/// @brief Called to handle mission item related messages. All messages should be passed to this method. /// @brief Called to handle mission item related messages. All messages should be passed to this method.
/// It will handle the appropriate set. /// It will handle the appropriate set.
/// @return true: message handled /// @return true: message handled
bool handleMessage(const mavlink_message_t& msg); bool handleMessage(const mavlink_message_t& msg);
typedef enum {
FailNone, // No failures
FailReadRequestListNoResponse, // Don't send MISSION_COUNT in response to MISSION_REQUEST_LIST
FailReadRequest0NoResponse, // Don't send MISSION_ITEM in response to MISSION_REQUEST item 0
FailReadRequest1NoResponse, // Don't send MISSION_ITEM in response to MISSION_REQUEST item 1
FailReadRequest0IncorrectSequence, // Respond to MISSION_REQUEST 0 with incorrect sequence number in MISSION_ITEM
FailReadRequest1IncorrectSequence, // Respond to MISSION_REQUEST 1 with incorrect sequence number in MISSION_ITEM
FailReadRequest0ErrorAck, // Respond to MISSION_REQUEST 0 with MISSION_ACK error
FailReadRequest1ErrorAck, // Respond to MISSION_REQUEST 1 bogus MISSION_ACK error
FailWriteRequest0NoResponse, // Don't respond to MISSION_COUNT with MISSION_REQUEST 0
FailWriteRequest1NoResponse, // Don't respond to MISSION_ITEM 0 with MISSION_REQUEST 1
FailWriteRequest0IncorrectSequence, // Respond to MISSION_COUNT 0 with MISSION_REQUEST with wrong sequence number
FailWriteRequest1IncorrectSequence, // Respond to MISSION_ITEM 0 with MISSION_REQUEST with wrong sequence number
FailWriteRequest0ErrorAck, // Respond to MISSION_COUNT 0 with MISSION_ACK error
FailWriteRequest1ErrorAck, // Respond to MISSION_ITEM 0 with MISSION_ACK error
FailWriteFinalAckNoResponse, // Don't send the final MISSION_ACK
FailWriteFinalAckErrorAck, // Send an error as the final MISSION_ACK
FailWriteFinalAckMissingRequests, // Send the MISSION_ACK before all items have been requested
} FailureMode_t;
/// Sets a failure mode for unit testing
/// @param failureMode Type of failure to simulate
/// @param firstTimeOnly true: fail first call, success subsequent calls, false: fail all calls
void setMissionItemFailureMode(FailureMode_t failureMode, bool firstTimeOnly);
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType);
/// Called to send a MISSION_ITEM message while the MissionManager is in idle state
void sendUnexpectedMissionItem(void);
/// Called to send a MISSION_REQUEST message while the MissionManager is in idle state
void sendUnexpectedMissionRequest(void);
/// Reset the state of the MissionItemHandler to no items, no transactions in progress.
void reset(void) { _missionItems.clear(); }
private slots:
void _missionItemResponseTimeout(void);
private: private:
void _handleMissionRequestList(const mavlink_message_t& msg); void _handleMissionRequestList(const mavlink_message_t& msg);
...@@ -52,6 +97,8 @@ private: ...@@ -52,6 +97,8 @@ private:
void _handleMissionItem(const mavlink_message_t& msg); void _handleMissionItem(const mavlink_message_t& msg);
void _handleMissionCount(const mavlink_message_t& msg); void _handleMissionCount(const mavlink_message_t& msg);
void _requestNextMissionItem(int sequenceNumber); void _requestNextMissionItem(int sequenceNumber);
void _sendAck(MAV_MISSION_RESULT ackType);
void _startMissionItemResponseTimer(void);
private: private:
MockLink* _mockLink; MockLink* _mockLink;
...@@ -61,6 +108,10 @@ private: ...@@ -61,6 +108,10 @@ private:
typedef QMap<uint16_t, mavlink_mission_item_t> MissionList_t; typedef QMap<uint16_t, mavlink_mission_item_t> MissionList_t;
MissionList_t _missionItems; MissionList_t _missionItems;
QTimer* _missionItemResponseTimer;
FailureMode_t _failureMode;
bool _failureFirstTimeOnly;
}; };
#endif #endif
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment