Commit ffb55f92 authored by DoinLakeFlyer's avatar DoinLakeFlyer

parent 04f50e70
......@@ -27,9 +27,9 @@ MissionManagerTest::MissionManagerTest(void)
}
void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, bool shouldFail)
void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult, bool shouldFail)
{
_mockLink->setMissionItemFailureMode(failureMode);
_mockLink->setMissionItemFailureMode(failureMode, failureAckResult);
// Setup our test case data
QList<MissionItem*> missionItems;
......@@ -115,11 +115,11 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
_multiSpyMissionManager->clearAllSignals();
}
void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode_t failureMode, bool shouldFail)
void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult, bool shouldFail)
{
_writeItems(MockLinkMissionItemHandler::FailNone, false);
_writeItems(MockLinkMissionItemHandler::FailNone, failureAckResult, false);
_mockLink->setMissionItemFailureMode(failureMode);
_mockLink->setMissionItemFailureMode(failureMode, failureAckResult);
// Read the items back from the vehicle
_missionManager->loadFromVehicle();
......@@ -253,8 +253,8 @@ void MissionManagerTest::_testWriteFailureHandlingWorker(void)
for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
const WriteTestCase_t* pCase = &rgTestCases[i];
qDebug() << "TEST CASE " << pCase->failureText;
_writeItems(pCase->failureMode, pCase->shouldFail);
qDebug() << "TEST CASE _testWriteFailureHandlingWorker" << pCase->failureText;
_writeItems(pCase->failureMode, MAV_MISSION_ERROR, pCase->shouldFail);
_mockLink->resetMissionItemHandler();
}
}
......@@ -298,8 +298,8 @@ void MissionManagerTest::_testReadFailureHandlingWorker(void)
for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
const ReadTestCase_t* pCase = &rgTestCases[i];
qDebug() << "TEST CASE " << pCase->failureText;
_roundTripItems(pCase->failureMode, pCase->shouldFail);
qDebug() << "TEST CASE _testReadFailureHandlingWorker" << pCase->failureText;
_roundTripItems(pCase->failureMode, MAV_MISSION_ERROR, pCase->shouldFail);
_mockLink->resetMissionItemHandler();
_multiSpyMissionManager->clearAllSignals();
}
......@@ -329,3 +329,34 @@ void MissionManagerTest::_testReadFailureHandlingPX4(void)
_initForFirmwareType(MAV_AUTOPILOT_PX4);
_testReadFailureHandlingWorker();
}
void MissionManagerTest::_testErrorAckFailureStrings(void)
{
_initForFirmwareType(MAV_AUTOPILOT_PX4);
typedef struct {
const char* ackResultStr;
MAV_MISSION_RESULT ackResult;
} ErrorStringTestCase_t;
static const ErrorStringTestCase_t rgTestCases[] = {
{ "MAV_MISSION_UNSUPPORTED_FRAME", MAV_MISSION_UNSUPPORTED_FRAME },
{ "MAV_MISSION_UNSUPPORTED", MAV_MISSION_UNSUPPORTED },
{ "MAV_MISSION_INVALID_PARAM1", MAV_MISSION_INVALID_PARAM1 },
{ "MAV_MISSION_INVALID_PARAM2", MAV_MISSION_INVALID_PARAM2 },
{ "MAV_MISSION_INVALID_PARAM3", MAV_MISSION_INVALID_PARAM3 },
{ "MAV_MISSION_INVALID_PARAM4", MAV_MISSION_INVALID_PARAM4 },
{ "MAV_MISSION_INVALID_PARAM5_X", MAV_MISSION_INVALID_PARAM5_X },
{ "MAV_MISSION_INVALID_PARAM6_Y", MAV_MISSION_INVALID_PARAM6_Y },
{ "MAV_MISSION_INVALID_PARAM7", MAV_MISSION_INVALID_PARAM7 },
{ "MAV_MISSION_INVALID_SEQUENCE", MAV_MISSION_INVALID_SEQUENCE },
};
for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
const ErrorStringTestCase_t* pCase = &rgTestCases[i];
qDebug() << "TEST CASE _testErrorAckFailureStrings" << pCase->ackResultStr;
_writeItems(MockLinkMissionItemHandler::FailWriteRequest1ErrorAck, pCase->ackResult, true /* shouldFail */);
_mockLink->resetMissionItemHandler();
}
}
......@@ -31,10 +31,11 @@ private slots:
void _testWriteFailureHandlingAPM(void);
void _testReadFailureHandlingPX4(void);
void _testReadFailureHandlingAPM(void);
void _testErrorAckFailureStrings(void);
private:
void _roundTripItems(MockLinkMissionItemHandler::FailureMode_t failureMode, bool shouldFail);
void _writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, bool shouldFail);
void _roundTripItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult, bool shouldFail);
void _writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult, bool shouldFail);
void _testWriteFailureHandlingWorker(void);
void _testReadFailureHandlingWorker(void);
......
......@@ -1013,9 +1013,9 @@ void MockLink::_respondWithAutopilotVersion(void)
respondWithMavlinkMessage(msg);
}
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
{
_missionItemHandler.setMissionItemFailureMode(failureMode);
_missionItemHandler.setFailureMode(failureMode, failureAckResult);
}
void MockLink::_sendHomePosition(void)
......
......@@ -134,7 +134,8 @@ public:
/// Sets a failure mode for unit testing
/// @param failureMode Type of failure to simulate
void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode);
/// @param failureAckResult Error to send if one the ack error modes
void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult);
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType) { _missionItemHandler.sendUnexpectedMissionAck(ackType); }
......
......@@ -200,7 +200,7 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
if ((_failureMode == FailReadRequest0ErrorAck && request.seq == 0) ||
(_failureMode == FailReadRequest1ErrorAck && request.seq == 1)) {
_sendAck(MAV_MISSION_ERROR);
_sendAck(_failureAckResult);
} else {
MissionItemBoth_t missionItemBoth;
......@@ -327,7 +327,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
if ((_failureMode == FailWriteRequest0ErrorAck && sequenceNumber == 0) ||
(_failureMode == FailWriteRequest1ErrorAck && sequenceNumber == 1)) {
qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem sending ack error due to failure mode";
_sendAck(MAV_MISSION_ERROR);
_sendAck(_failureAckResult);
} else {
mavlink_message_t message;
......@@ -408,7 +408,7 @@ void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg
_writeSequenceIndex++;
if (_writeSequenceIndex < _writeSequenceCount) {
if (_failureMode == FailWriteFinalAckMissingRequests && _writeSequenceIndex == 3) {
// Send MAV_MISSION_ACCPETED ack too early
// Send MAV_MISSION_ACCEPTED ack too early
_sendAck(MAV_MISSION_ACCEPTED);
} else {
_requestNextMissionItem(_writeSequenceIndex);
......@@ -448,9 +448,10 @@ void MockLinkMissionItemHandler::sendUnexpectedMissionRequest(void)
Q_ASSERT(false);
}
void MockLinkMissionItemHandler::setMissionItemFailureMode(FailureMode_t failureMode)
void MockLinkMissionItemHandler::setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
{
_failureMode = failureMode;
_failureAckResult = failureAckResult;
}
void MockLinkMissionItemHandler::shutdown(void)
......
......@@ -63,7 +63,8 @@ public:
/// Sets a failure mode for unit testing
/// @param failureMode Type of failure to simulate
void setMissionItemFailureMode(FailureMode_t failureMode);
/// @param failureAckResult Error to send if one the ack error modes
void setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult);
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType);
......@@ -115,6 +116,7 @@ private:
QTimer* _missionItemResponseTimer;
FailureMode_t _failureMode;
MAV_MISSION_RESULT _failureAckResult;
bool _sendHomePositionOnEmptyList;
MAVLinkProtocol* _mavlinkProtocol;
bool _failReadRequestListFirstResponse;
......
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