Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
ffb55f92
Commit
ffb55f92
authored
Mar 08, 2020
by
DoinLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
04f50e70
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
55 additions
and
19 deletions
+55
-19
MissionManagerTest.cc
src/MissionManager/MissionManagerTest.cc
+40
-9
MissionManagerTest.h
src/MissionManager/MissionManagerTest.h
+3
-2
MockLink.cc
src/comm/MockLink.cc
+2
-2
MockLink.h
src/comm/MockLink.h
+2
-1
MockLinkMissionItemHandler.cc
src/comm/MockLinkMissionItemHandler.cc
+5
-4
MockLinkMissionItemHandler.h
src/comm/MockLinkMissionItemHandler.h
+3
-1
No files found.
src/MissionManager/MissionManagerTest.cc
View file @
ffb55f92
...
@@ -27,9 +27,9 @@ MissionManagerTest::MissionManagerTest(void)
...
@@ -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
// Setup our test case data
QList
<
MissionItem
*>
missionItems
;
QList
<
MissionItem
*>
missionItems
;
...
@@ -115,11 +115,11 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
...
@@ -115,11 +115,11 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
_multiSpyMissionManager
->
clearAllSignals
();
_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
,
fa
ilureAckResult
,
fa
lse
);
_mockLink
->
setMissionItemFailureMode
(
failureMode
);
_mockLink
->
setMissionItemFailureMode
(
failureMode
,
failureAckResult
);
// Read the items back from the vehicle
// Read the items back from the vehicle
_missionManager
->
loadFromVehicle
();
_missionManager
->
loadFromVehicle
();
...
@@ -253,8 +253,8 @@ void MissionManagerTest::_testWriteFailureHandlingWorker(void)
...
@@ -253,8 +253,8 @@ void MissionManagerTest::_testWriteFailureHandlingWorker(void)
for
(
size_t
i
=
0
;
i
<
sizeof
(
rgTestCases
)
/
sizeof
(
rgTestCases
[
0
]);
i
++
)
{
for
(
size_t
i
=
0
;
i
<
sizeof
(
rgTestCases
)
/
sizeof
(
rgTestCases
[
0
]);
i
++
)
{
const
WriteTestCase_t
*
pCase
=
&
rgTestCases
[
i
];
const
WriteTestCase_t
*
pCase
=
&
rgTestCases
[
i
];
qDebug
()
<<
"TEST CASE "
<<
pCase
->
failureText
;
qDebug
()
<<
"TEST CASE
_testWriteFailureHandlingWorker
"
<<
pCase
->
failureText
;
_writeItems
(
pCase
->
failureMode
,
pCase
->
shouldFail
);
_writeItems
(
pCase
->
failureMode
,
MAV_MISSION_ERROR
,
pCase
->
shouldFail
);
_mockLink
->
resetMissionItemHandler
();
_mockLink
->
resetMissionItemHandler
();
}
}
}
}
...
@@ -298,8 +298,8 @@ void MissionManagerTest::_testReadFailureHandlingWorker(void)
...
@@ -298,8 +298,8 @@ void MissionManagerTest::_testReadFailureHandlingWorker(void)
for
(
size_t
i
=
0
;
i
<
sizeof
(
rgTestCases
)
/
sizeof
(
rgTestCases
[
0
]);
i
++
)
{
for
(
size_t
i
=
0
;
i
<
sizeof
(
rgTestCases
)
/
sizeof
(
rgTestCases
[
0
]);
i
++
)
{
const
ReadTestCase_t
*
pCase
=
&
rgTestCases
[
i
];
const
ReadTestCase_t
*
pCase
=
&
rgTestCases
[
i
];
qDebug
()
<<
"TEST CASE "
<<
pCase
->
failureText
;
qDebug
()
<<
"TEST CASE
_testReadFailureHandlingWorker
"
<<
pCase
->
failureText
;
_roundTripItems
(
pCase
->
failureMode
,
pCase
->
shouldFail
);
_roundTripItems
(
pCase
->
failureMode
,
MAV_MISSION_ERROR
,
pCase
->
shouldFail
);
_mockLink
->
resetMissionItemHandler
();
_mockLink
->
resetMissionItemHandler
();
_multiSpyMissionManager
->
clearAllSignals
();
_multiSpyMissionManager
->
clearAllSignals
();
}
}
...
@@ -329,3 +329,34 @@ void MissionManagerTest::_testReadFailureHandlingPX4(void)
...
@@ -329,3 +329,34 @@ void MissionManagerTest::_testReadFailureHandlingPX4(void)
_initForFirmwareType
(
MAV_AUTOPILOT_PX4
);
_initForFirmwareType
(
MAV_AUTOPILOT_PX4
);
_testReadFailureHandlingWorker
();
_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
();
}
}
src/MissionManager/MissionManagerTest.h
View file @
ffb55f92
...
@@ -31,10 +31,11 @@ private slots:
...
@@ -31,10 +31,11 @@ private slots:
void
_testWriteFailureHandlingAPM
(
void
);
void
_testWriteFailureHandlingAPM
(
void
);
void
_testReadFailureHandlingPX4
(
void
);
void
_testReadFailureHandlingPX4
(
void
);
void
_testReadFailureHandlingAPM
(
void
);
void
_testReadFailureHandlingAPM
(
void
);
void
_testErrorAckFailureStrings
(
void
);
private:
private:
void
_roundTripItems
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
,
bool
shouldFail
);
void
_roundTripItems
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
,
MAV_MISSION_RESULT
failureAckResult
,
bool
shouldFail
);
void
_writeItems
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
,
bool
shouldFail
);
void
_writeItems
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
,
MAV_MISSION_RESULT
failureAckResult
,
bool
shouldFail
);
void
_testWriteFailureHandlingWorker
(
void
);
void
_testWriteFailureHandlingWorker
(
void
);
void
_testReadFailureHandlingWorker
(
void
);
void
_testReadFailureHandlingWorker
(
void
);
...
...
src/comm/MockLink.cc
View file @
ffb55f92
...
@@ -1013,9 +1013,9 @@ void MockLink::_respondWithAutopilotVersion(void)
...
@@ -1013,9 +1013,9 @@ void MockLink::_respondWithAutopilotVersion(void)
respondWithMavlinkMessage
(
msg
);
respondWithMavlinkMessage
(
msg
);
}
}
void
MockLink
::
setMissionItemFailureMode
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
)
void
MockLink
::
setMissionItemFailureMode
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
,
MAV_MISSION_RESULT
failureAckResult
)
{
{
_missionItemHandler
.
set
MissionItemFailureMode
(
failureMode
);
_missionItemHandler
.
set
FailureMode
(
failureMode
,
failureAckResult
);
}
}
void
MockLink
::
_sendHomePosition
(
void
)
void
MockLink
::
_sendHomePosition
(
void
)
...
...
src/comm/MockLink.h
View file @
ffb55f92
...
@@ -134,7 +134,8 @@ public:
...
@@ -134,7 +134,8 @@ public:
/// Sets a failure mode for unit testing
/// Sets a failure mode for unit testing
/// @param failureMode Type of failure to simulate
/// @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
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
void
sendUnexpectedMissionAck
(
MAV_MISSION_RESULT
ackType
)
{
_missionItemHandler
.
sendUnexpectedMissionAck
(
ackType
);
}
void
sendUnexpectedMissionAck
(
MAV_MISSION_RESULT
ackType
)
{
_missionItemHandler
.
sendUnexpectedMissionAck
(
ackType
);
}
...
...
src/comm/MockLinkMissionItemHandler.cc
View file @
ffb55f92
...
@@ -200,7 +200,7 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
...
@@ -200,7 +200,7 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
if
((
_failureMode
==
FailReadRequest0ErrorAck
&&
request
.
seq
==
0
)
||
if
((
_failureMode
==
FailReadRequest0ErrorAck
&&
request
.
seq
==
0
)
||
(
_failureMode
==
FailReadRequest1ErrorAck
&&
request
.
seq
==
1
))
{
(
_failureMode
==
FailReadRequest1ErrorAck
&&
request
.
seq
==
1
))
{
_sendAck
(
MAV_MISSION_ERROR
);
_sendAck
(
_failureAckResult
);
}
else
{
}
else
{
MissionItemBoth_t
missionItemBoth
;
MissionItemBoth_t
missionItemBoth
;
...
@@ -327,7 +327,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
...
@@ -327,7 +327,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
if
((
_failureMode
==
FailWriteRequest0ErrorAck
&&
sequenceNumber
==
0
)
||
if
((
_failureMode
==
FailWriteRequest0ErrorAck
&&
sequenceNumber
==
0
)
||
(
_failureMode
==
FailWriteRequest1ErrorAck
&&
sequenceNumber
==
1
))
{
(
_failureMode
==
FailWriteRequest1ErrorAck
&&
sequenceNumber
==
1
))
{
qCDebug
(
MockLinkMissionItemHandlerLog
)
<<
"_requestNextMissionItem sending ack error due to failure mode"
;
qCDebug
(
MockLinkMissionItemHandlerLog
)
<<
"_requestNextMissionItem sending ack error due to failure mode"
;
_sendAck
(
MAV_MISSION_ERROR
);
_sendAck
(
_failureAckResult
);
}
else
{
}
else
{
mavlink_message_t
message
;
mavlink_message_t
message
;
...
@@ -408,7 +408,7 @@ void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg
...
@@ -408,7 +408,7 @@ void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t& msg
_writeSequenceIndex
++
;
_writeSequenceIndex
++
;
if
(
_writeSequenceIndex
<
_writeSequenceCount
)
{
if
(
_writeSequenceIndex
<
_writeSequenceCount
)
{
if
(
_failureMode
==
FailWriteFinalAckMissingRequests
&&
_writeSequenceIndex
==
3
)
{
if
(
_failureMode
==
FailWriteFinalAckMissingRequests
&&
_writeSequenceIndex
==
3
)
{
// Send MAV_MISSION_ACC
PE
TED ack too early
// Send MAV_MISSION_ACC
EP
TED ack too early
_sendAck
(
MAV_MISSION_ACCEPTED
);
_sendAck
(
MAV_MISSION_ACCEPTED
);
}
else
{
}
else
{
_requestNextMissionItem
(
_writeSequenceIndex
);
_requestNextMissionItem
(
_writeSequenceIndex
);
...
@@ -448,9 +448,10 @@ void MockLinkMissionItemHandler::sendUnexpectedMissionRequest(void)
...
@@ -448,9 +448,10 @@ void MockLinkMissionItemHandler::sendUnexpectedMissionRequest(void)
Q_ASSERT
(
false
);
Q_ASSERT
(
false
);
}
}
void
MockLinkMissionItemHandler
::
set
MissionItemFailureMode
(
FailureMode_t
failureMode
)
void
MockLinkMissionItemHandler
::
set
FailureMode
(
FailureMode_t
failureMode
,
MAV_MISSION_RESULT
failureAckResult
)
{
{
_failureMode
=
failureMode
;
_failureMode
=
failureMode
;
_failureAckResult
=
failureAckResult
;
}
}
void
MockLinkMissionItemHandler
::
shutdown
(
void
)
void
MockLinkMissionItemHandler
::
shutdown
(
void
)
...
...
src/comm/MockLinkMissionItemHandler.h
View file @
ffb55f92
...
@@ -63,7 +63,8 @@ public:
...
@@ -63,7 +63,8 @@ public:
/// Sets a failure mode for unit testing
/// Sets a failure mode for unit testing
/// @param failureMode Type of failure to simulate
/// @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
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
void
sendUnexpectedMissionAck
(
MAV_MISSION_RESULT
ackType
);
void
sendUnexpectedMissionAck
(
MAV_MISSION_RESULT
ackType
);
...
@@ -115,6 +116,7 @@ private:
...
@@ -115,6 +116,7 @@ private:
QTimer
*
_missionItemResponseTimer
;
QTimer
*
_missionItemResponseTimer
;
FailureMode_t
_failureMode
;
FailureMode_t
_failureMode
;
MAV_MISSION_RESULT
_failureAckResult
;
bool
_sendHomePositionOnEmptyList
;
bool
_sendHomePositionOnEmptyList
;
MAVLinkProtocol
*
_mavlinkProtocol
;
MAVLinkProtocol
*
_mavlinkProtocol
;
bool
_failReadRequestListFirstResponse
;
bool
_failReadRequestListFirstResponse
;
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment