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
bc71d49d
Commit
bc71d49d
authored
May 12, 2015
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #1557 from DonLakeFlyer/FileManager
File Manager fixes and unit test
parents
886b40b5
f534aa7e
Changes
11
Hide whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
417 additions
and
481 deletions
+417
-481
QGCApplication.pro
QGCApplication.pro
+4
-3
MockLink.cc
src/comm/MockLink.cc
+29
-18
MockLink.h
src/comm/MockLink.h
+9
-1
MockLinkFileServer.cc
src/comm/MockLinkFileServer.cc
+88
-73
MockLinkFileServer.h
src/comm/MockLinkFileServer.h
+27
-26
FileManagerTest.cc
src/qgcunittest/FileManagerTest.cc
+201
-269
FileManagerTest.h
src/qgcunittest/FileManagerTest.h
+5
-12
MockMavlinkInterface.cc
src/qgcunittest/MockMavlinkInterface.cc
+0
-9
MockMavlinkInterface.h
src/qgcunittest/MockMavlinkInterface.h
+0
-44
FileManager.cc
src/uas/FileManager.cc
+51
-22
FileManager.h
src/uas/FileManager.h
+3
-4
No files found.
QGCApplication.pro
View file @
bc71d49d
...
...
@@ -236,6 +236,7 @@ HEADERS += \
src
/
comm
/
LinkManager
.
h
\
src
/
comm
/
MAVLinkProtocol
.
h
\
src
/
comm
/
MockLink
.
h
\
src
/
comm
/
MockLinkFileServer
.
h
\
src
/
comm
/
MockLinkMissionItemHandler
.
h
\
src
/
comm
/
ProtocolInterface
.
h
\
src
/
comm
/
QGCFlightGearLink
.
h
\
...
...
@@ -374,6 +375,7 @@ SOURCES += \
src
/
comm
/
LinkManager
.
cc
\
src
/
comm
/
MAVLinkProtocol
.
cc
\
src
/
comm
/
MockLink
.
cc
\
src
/
comm
/
MockLinkFileServer
.
cc
\
src
/
comm
/
MockLinkMissionItemHandler
.
cc
\
src
/
comm
/
QGCFlightGearLink
.
cc
\
src
/
comm
/
QGCJSBSimLink
.
cc
\
...
...
@@ -518,8 +520,6 @@ INCLUDEPATH += \
HEADERS
+=
\
src
/
qgcunittest
/
FlightGearTest
.
h
\
src
/
qgcunittest
/
MockMavlinkFileServer
.
h
\
src
/
qgcunittest
/
MockMavlinkInterface
.
h
\
src
/
qgcunittest
/
MultiSignalSpy
.
h
\
src
/
qgcunittest
/
TCPLinkTest
.
h
\
src
/
qgcunittest
/
TCPLoopBackServer
.
h
\
...
...
@@ -534,10 +534,10 @@ HEADERS += \
src
/
qgcunittest
/
PX4RCCalibrationTest
.
h
\
src
/
qgcunittest
/
UnitTest
.
h
\
src
/
VehicleSetup
/
SetupViewTest
.
h
\
src
/
qgcunittest
/
FileManagerTest
.
h
\
SOURCES
+=
\
src
/
qgcunittest
/
FlightGearTest
.
cc
\
src
/
qgcunittest
/
MockMavlinkFileServer
.
cc
\
src
/
qgcunittest
/
MultiSignalSpy
.
cc
\
src
/
qgcunittest
/
TCPLinkTest
.
cc
\
src
/
qgcunittest
/
TCPLoopBackServer
.
cc
\
...
...
@@ -552,6 +552,7 @@ SOURCES += \
src
/
qgcunittest
/
PX4RCCalibrationTest
.
cc
\
src
/
qgcunittest
/
UnitTest
.
cc
\
src
/
VehicleSetup
/
SetupViewTest
.
cc
\
src
/
qgcunittest
/
FileManagerTest
.
cc
\
}
#
DebugBuild
|
WindowsDebugAndRelease
}
#
AndroidBuild
...
...
src/comm/MockLink.cc
View file @
bc71d49d
...
...
@@ -75,7 +75,8 @@ MockLink::MockLink(MockConfiguration* config) :
_mavlinkStarted
(
false
),
_mavBaseMode
(
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
|
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
),
_mavState
(
MAV_STATE_STANDBY
),
_autopilotType
(
MAV_AUTOPILOT_PX4
)
_autopilotType
(
MAV_AUTOPILOT_PX4
),
_fileServer
(
NULL
)
{
_config
=
config
;
union
px4_custom_mode
px4_cm
;
...
...
@@ -84,6 +85,9 @@ MockLink::MockLink(MockConfiguration* config) :
px4_cm
.
main_mode
=
PX4_CUSTOM_MAIN_MODE_MANUAL
;
_mavCustomMode
=
px4_cm
.
data
;
_fileServer
=
new
MockLinkFileServer
(
_vehicleSystemId
,
_vehicleComponentId
,
this
);
Q_CHECK_PTR
(
_fileServer
);
_missionItemHandler
=
new
MockLinkMissionItemHandler
(
_vehicleSystemId
,
this
);
Q_CHECK_PTR
(
_missionItemHandler
);
...
...
@@ -218,7 +222,6 @@ void MockLink::_loadParams(void)
void
MockLink
::
_sendHeartBeat
(
void
)
{
mavlink_message_t
msg
;
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
mavlink_msg_heartbeat_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
...
...
@@ -228,7 +231,14 @@ void MockLink::_sendHeartBeat(void)
_mavBaseMode
,
// MAV_MODE
_mavCustomMode
,
// custom mode
_mavState
);
// MAV_STATE
respondWithMavlinkMessage
(
msg
);
}
void
MockLink
::
respondWithMavlinkMessage
(
const
mavlink_message_t
&
msg
)
{
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
int
cBuffer
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
QByteArray
bytes
((
char
*
)
buffer
,
cBuffer
);
emit
bytesReceived
(
this
,
bytes
);
...
...
@@ -332,6 +342,10 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
_handleMissionCount(msg);
break;
#endif
case
MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL
:
_handleFTP
(
msg
);
break
;
default:
qDebug
()
<<
"MockLink: Unhandled mavlink message, id:"
<<
msg
.
msgid
;
...
...
@@ -340,15 +354,6 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
}
}
void
MockLink
::
_emitMavlinkMessage
(
const
mavlink_message_t
&
msg
)
{
uint8_t
outputBuffer
[
MAVLINK_MAX_PACKET_LEN
];
int
cBuffer
=
mavlink_msg_to_send_buffer
(
outputBuffer
,
&
msg
);
QByteArray
bytes
((
char
*
)
outputBuffer
,
cBuffer
);
emit
bytesReceived
(
this
,
bytes
);
}
void
MockLink
::
_handleHeartBeat
(
const
mavlink_message_t
&
msg
)
{
Q_UNUSED
(
msg
);
...
...
@@ -494,7 +499,7 @@ void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
paramType
,
// MAV_PARAM_TYPE
cParameters
,
// Total number of parameters
paramIndex
++
);
// Index of this parameter
_emit
MavlinkMessage
(
responseMsg
);
respondWith
MavlinkMessage
(
responseMsg
);
// Only first parameter the first time through
break
;
...
...
@@ -533,7 +538,7 @@ void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
paramType
,
// MAV_PARAM_TYPE
cParameters
,
// Total number of parameters
paramIndex
++
);
// Index of this parameter
_emit
MavlinkMessage
(
responseMsg
);
respondWith
MavlinkMessage
(
responseMsg
);
}
}
}
...
...
@@ -571,7 +576,7 @@ void MockLink::_handleParamSet(const mavlink_message_t& msg)
request
.
param_type
,
// Send same type back
_mapParamName2Value
[
componentId
].
count
(),
// Total number of parameters
_mapParamName2Value
[
componentId
].
keys
().
indexOf
(
paramId
));
// Index of this parameter
_emit
MavlinkMessage
(
responseMsg
);
respondWith
MavlinkMessage
(
responseMsg
);
}
void
MockLink
::
_handleParamRequestRead
(
const
mavlink_message_t
&
msg
)
...
...
@@ -613,7 +618,7 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
_mapParamName2MavParamType
[
paramId
],
// Parameter type
_mapParamName2Value
[
componentId
].
count
(),
// Total number of parameters
_mapParamName2Value
[
componentId
].
keys
().
indexOf
(
paramId
));
// Index of this parameter
_emit
MavlinkMessage
(
responseMsg
);
respondWith
MavlinkMessage
(
responseMsg
);
}
void
MockLink
::
_handleMissionRequestList
(
const
mavlink_message_t
&
msg
)
...
...
@@ -632,7 +637,7 @@ void MockLink::_handleMissionRequestList(const mavlink_message_t& msg)
msg
.
sysid
,
// Target is original sender
msg
.
compid
,
// Target is original sender
_missionItems
.
count
());
// Number of mission items
_emit
MavlinkMessage
(
responseMsg
);
respondWith
MavlinkMessage
(
responseMsg
);
}
void
MockLink
::
_handleMissionRequest
(
const
mavlink_message_t
&
msg
)
...
...
@@ -660,7 +665,7 @@ void MockLink::_handleMissionRequest(const mavlink_message_t& msg)
item
.
autocontinue
,
item
.
param1
,
item
.
param2
,
item
.
param3
,
item
.
param4
,
item
.
x
,
item
.
y
,
item
.
z
);
_emit
MavlinkMessage
(
responseMsg
);
respondWith
MavlinkMessage
(
responseMsg
);
}
void
MockLink
::
_handleMissionItem
(
const
mavlink_message_t
&
msg
)
...
...
@@ -711,5 +716,11 @@ void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
chanRaw
[
16
],
// channel raw value
chanRaw
[
17
],
// channel raw value
0
);
// rss
_emitMavlinkMessage
(
responseMsg
);
respondWithMavlinkMessage
(
responseMsg
);
}
void
MockLink
::
_handleFTP
(
const
mavlink_message_t
&
msg
)
{
Q_ASSERT
(
_fileServer
);
_fileServer
->
handleFTPMessage
(
msg
);
}
src/comm/MockLink.h
View file @
bc71d49d
...
...
@@ -28,6 +28,7 @@
#include <QLoggingCategory>
#include "MockLinkMissionItemHandler.h"
#include "MockLinkFileServer.h"
#include "LinkManager.h"
#include "QGCMAVLink.h"
...
...
@@ -71,6 +72,11 @@ public:
MAV_AUTOPILOT
getAutopilotType
(
void
)
{
return
_autopilotType
;
}
void
setAutopilotType
(
MAV_AUTOPILOT
autopilot
)
{
_autopilotType
=
autopilot
;
}
void
emitRemoteControlChannelRawChanged
(
int
channel
,
uint16_t
raw
);
/// Sends the specified mavlink message to QGC
void
respondWithMavlinkMessage
(
const
mavlink_message_t
&
msg
);
MockLinkFileServer
*
getFileServer
(
void
)
{
return
_fileServer
;
}
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
...
...
@@ -109,7 +115,6 @@ private:
void
_handleIncomingNSHBytes
(
const
char
*
bytes
,
int
cBytes
);
void
_handleIncomingMavlinkBytes
(
const
uint8_t
*
bytes
,
int
cBytes
);
void
_loadParams
(
void
);
void
_emitMavlinkMessage
(
const
mavlink_message_t
&
msg
);
void
_handleHeartBeat
(
const
mavlink_message_t
&
msg
);
void
_handleSetMode
(
const
mavlink_message_t
&
msg
);
void
_handleParamRequestList
(
const
mavlink_message_t
&
msg
);
...
...
@@ -118,6 +123,7 @@ private:
void
_handleMissionRequestList
(
const
mavlink_message_t
&
msg
);
void
_handleMissionRequest
(
const
mavlink_message_t
&
msg
);
void
_handleMissionItem
(
const
mavlink_message_t
&
msg
);
void
_handleFTP
(
const
mavlink_message_t
&
msg
);
float
_floatUnionForParam
(
int
componentId
,
const
QString
&
paramName
);
void
_setParamFloatUnionIntoMap
(
int
componentId
,
const
QString
&
paramName
,
float
paramFloat
);
...
...
@@ -144,6 +150,8 @@ private:
MockConfiguration
*
_config
;
MAV_AUTOPILOT
_autopilotType
;
MockLinkFileServer
*
_fileServer
;
};
#endif
src/
qgcunittest/MockMavl
inkFileServer.cc
→
src/
comm/MockL
inkFileServer.cc
View file @
bc71d49d
...
...
@@ -21,18 +21,19 @@
======================================================================*/
#include "MockMavlinkFileServer.h"
const
MockMavlinkFileServer
::
ErrorMode_t
MockMavlinkFileServer
::
rgFailureModes
[]
=
{
MockMavlinkFileServer
::
errModeNoResponse
,
MockMavlinkFileServer
::
errModeNakResponse
,
MockMavlinkFileServer
::
errModeNoSecondResponse
,
MockMavlinkFileServer
::
errModeNakSecondResponse
,
MockMavlinkFileServer
::
errModeBadSequence
,
#include "MockLinkFileServer.h"
#include "MockLink.h"
const
MockLinkFileServer
::
ErrorMode_t
MockLinkFileServer
::
rgFailureModes
[]
=
{
MockLinkFileServer
::
errModeNoResponse
,
MockLinkFileServer
::
errModeNakResponse
,
MockLinkFileServer
::
errModeNoSecondResponse
,
MockLinkFileServer
::
errModeNakSecondResponse
,
MockLinkFileServer
::
errModeBadSequence
,
};
const
size_t
Mock
MavlinkFileServer
::
cFailureModes
=
sizeof
(
MockMavlinkFileServer
::
rgFailureModes
)
/
sizeof
(
MockMavl
inkFileServer
::
rgFailureModes
[
0
]);
const
size_t
Mock
LinkFileServer
::
cFailureModes
=
sizeof
(
MockLinkFileServer
::
rgFailureModes
)
/
sizeof
(
MockL
inkFileServer
::
rgFailureModes
[
0
]);
const
Mock
MavlinkFileServer
::
FileTestCase
MockMavlinkFileServer
::
rgFileTestCases
[
MockMavl
inkFileServer
::
cFileTestCases
]
=
{
const
Mock
LinkFileServer
::
FileTestCase
MockLinkFileServer
::
rgFileTestCases
[
MockL
inkFileServer
::
cFileTestCases
]
=
{
// File fits one Read Ack packet, partially filling data
{
"partial.qgc"
,
sizeof
(((
FileManager
::
Request
*
)
0
)
->
data
)
-
1
,
1
,
false
},
// File fits one Read Ack packet, exactly filling all data
...
...
@@ -42,19 +43,20 @@ const MockMavlinkFileServer::FileTestCase MockMavlinkFileServer::rgFileTestCases
};
// We only support a single fixed session
const
uint8_t
Mock
Mavl
inkFileServer
::
_sessionId
=
1
;
const
uint8_t
Mock
L
inkFileServer
::
_sessionId
=
1
;
Mock
MavlinkFileServer
::
MockMavlinkFileServer
(
uint8_t
systemIdQGC
,
uint8_t
systemIdServer
)
:
Mock
LinkFileServer
::
MockLinkFileServer
(
uint8_t
systemIdServer
,
uint8_t
componentIdServer
,
MockLink
*
mockLink
)
:
_errMode
(
errModeNone
),
_systemIdServer
(
systemIdServer
),
_systemIdQGC
(
systemIdQGC
)
_componentIdServer
(
componentIdServer
),
_mockLink
(
mockLink
)
{
}
/// @brief Handles List command requests. Only supports root folder paths.
/// File list returned is set using the setFileList method.
void
Mock
MavlinkFileServer
::
_listCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
void
Mock
LinkFileServer
::
_listCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
{
// FIXME: Does not support directories that span multiple packets
...
...
@@ -65,17 +67,18 @@ void MockMavlinkFileServer::_listCommand(FileManager::Request* request, uint16_t
// We only support root path
path
=
(
char
*
)
&
request
->
data
[
0
];
if
(
!
path
.
isEmpty
()
&&
path
!=
"/"
)
{
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
return
;
}
// Offset requested is past the end of the list
if
(
request
->
hdr
.
offset
>
(
uint32_t
)
_fileList
.
size
())
{
_sendNak
(
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
return
;
}
ackResponse
.
hdr
.
opcode
=
FileManager
::
kRspAck
;
ackResponse
.
hdr
.
req_opcode
=
FileManager
::
kCmdListDirectory
;
ackResponse
.
hdr
.
session
=
0
;
ackResponse
.
hdr
.
offset
=
request
->
hdr
.
offset
;
ackResponse
.
hdr
.
size
=
0
;
...
...
@@ -92,22 +95,22 @@ void MockMavlinkFileServer::_listCommand(FileManager::Request* request, uint16_t
bufPtr
+=
cchFilename
+
1
;
}
_
emitResponse
(
&
ackResponse
,
outgoingSeqNumber
);
_
sendResponse
(
senderSystemId
,
senderComponentId
,
&
ackResponse
,
outgoingSeqNumber
);
}
else
if
(
_errMode
==
errModeNakSecondResponse
)
{
// Nak error all subsequent requests
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
return
;
}
else
if
(
_errMode
==
errModeNoSecondResponse
)
{
// No response for all subsequent requests
return
;
}
else
{
// FIXME: Does not support directories that span multiple packets
_sendNak
(
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdListDirectory
);
}
}
/// @brief Handles Open command requests.
void
Mock
MavlinkFileServer
::
_openCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
void
Mock
LinkFileServer
::
_openCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
{
FileManager
::
Request
response
;
QString
path
;
...
...
@@ -129,7 +132,7 @@ void MockMavlinkFileServer::_openCommand(FileManager::Request* request, uint16_t
}
}
if
(
!
found
)
{
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdOpenFileRO
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdOpenFileRO
);
return
;
}
...
...
@@ -141,16 +144,16 @@ void MockMavlinkFileServer::_openCommand(FileManager::Request* request, uint16_t
response
.
hdr
.
size
=
sizeof
(
uint32_t
);
response
.
openFileLength
=
_readFileLength
;
_
emitResponse
(
&
response
,
outgoingSeqNumber
);
_
sendResponse
(
senderSystemId
,
senderComponentId
,
&
response
,
outgoingSeqNumber
);
}
void
Mock
MavlinkFileServer
::
_readCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
void
Mock
LinkFileServer
::
_readCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
{
FileManager
::
Request
response
;
uint16_t
outgoingSeqNumber
=
_nextSeqNumber
(
seqNumber
);
if
(
request
->
hdr
.
session
!=
_sessionId
)
{
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdReadFile
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdReadFile
);
return
;
}
...
...
@@ -161,7 +164,7 @@ void MockMavlinkFileServer::_readCommand(FileManager::Request* request, uint16_t
// If we get here it means the client is requesting additional data past the first request
if
(
_errMode
==
errModeNakSecondResponse
)
{
// Nak error all subsequent requests
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdReadFile
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdReadFile
);
return
;
}
else
if
(
_errMode
==
errModeNoSecondResponse
)
{
// No rsponse for all subsequent requests
...
...
@@ -170,7 +173,7 @@ void MockMavlinkFileServer::_readCommand(FileManager::Request* request, uint16_t
}
if
(
readOffset
>=
_readFileLength
)
{
_sendNak
(
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdReadFile
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdReadFile
);
return
;
}
...
...
@@ -188,16 +191,16 @@ void MockMavlinkFileServer::_readCommand(FileManager::Request* request, uint16_t
response
.
hdr
.
opcode
=
FileManager
::
kRspAck
;
response
.
hdr
.
req_opcode
=
FileManager
::
kCmdReadFile
;
_
emitResponse
(
&
response
,
outgoingSeqNumber
);
_
sendResponse
(
senderSystemId
,
senderComponentId
,
&
response
,
outgoingSeqNumber
);
}
void
Mock
MavlinkFileServer
::
_streamCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
void
Mock
LinkFileServer
::
_streamCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
{
uint16_t
outgoingSeqNumber
=
_nextSeqNumber
(
seqNumber
);
FileManager
::
Request
response
;
if
(
request
->
hdr
.
session
!=
_sessionId
)
{
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdBurstReadFile
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdBurstReadFile
);
return
;
}
...
...
@@ -212,7 +215,7 @@ void MockMavlinkFileServer::_streamCommand(FileManager::Request* request, uint16
// If we get here it means the client is requesting additional data past the first request
if
(
_errMode
==
errModeNakSecondResponse
)
{
// Nak error all subsequent requests
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdBurstReadFile
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
FileManager
::
kCmdBurstReadFile
);
return
;
}
else
if
(
_errMode
==
errModeNoSecondResponse
)
{
// No response for all subsequent requests
...
...
@@ -234,55 +237,67 @@ void MockMavlinkFileServer::_streamCommand(FileManager::Request* request, uint16
response
.
hdr
.
opcode
=
FileManager
::
kRspAck
;
response
.
hdr
.
req_opcode
=
FileManager
::
kCmdBurstReadFile
;
_
emitResponse
(
&
response
,
outgoingSeqNumber
);
_
sendResponse
(
senderSystemId
,
senderComponentId
,
&
response
,
outgoingSeqNumber
);
outgoingSeqNumber
=
_nextSeqNumber
(
outgoingSeqNumber
);
ackOffset
+=
cDataAck
;
}
_sendNak
(
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdBurstReadFile
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrEOF
,
outgoingSeqNumber
,
FileManager
::
kCmdBurstReadFile
);
}
/// @brief Handles Terminate commands
void
MockMavlinkFileServer
::
_terminateCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
void
MockLinkFileServer
::
_terminateCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
{
uint16_t
outgoingSeqNumber
=
_nextSeqNumber
(
seqNumber
);
if
(
request
->
hdr
.
session
!=
_sessionId
)
{
_sendNak
(
FileManager
::
kErrInvalidSession
,
outgoingSeqNumber
,
FileManager
::
kCmdTerminateSession
);
_sendNak
(
senderSystemId
,
senderComponentId
,
FileManager
::
kErrInvalidSession
,
outgoingSeqNumber
,
FileManager
::
kCmdTerminateSession
);
return
;
}
_sendAck
(
outgoingSeqNumber
,
FileManager
::
kCmdTerminateSession
);
_sendAck
(
senderSystemId
,
senderComponentId
,
outgoingSeqNumber
,
FileManager
::
kCmdTerminateSession
);
// Let our test harness know that we got a terminate command. This is used to validate the a Terminate is correctly
// sent after an Open.
emit
terminateCommandReceived
();
}
/// @brief Handles messages sent to the FTP server.
void
MockMavlinkFileServer
::
sendMessage
(
mavlink_message_t
message
)
void
MockLinkFileServer
::
_resetCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
uint16_t
seqNumber
)
{
FileManager
::
Request
ackResponse
;
uint16_t
outgoingSeqNumber
=
_nextSeqNumber
(
seqNumber
);
_sendAck
(
senderSystemId
,
senderComponentId
,
outgoingSeqNumber
,
FileManager
::
kCmdResetSessions
);
emit
resetCommandReceived
();
}
Q_ASSERT
(
message
.
msgid
==
MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL
);
void
MockLinkFileServer
::
handleFTPMessage
(
const
mavlink_message_t
&
message
)
{
if
(
message
.
msgid
!=
MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL
)
{
return
;
}
mavlink_file_transfer_protocol_t
requestFileTransferProtocol
;
mavlink_msg_file_transfer_protocol_decode
(
&
message
,
&
requestFileTransferProtocol
);
FileManager
::
Request
*
request
=
(
FileManager
::
Request
*
)
&
requestFileTransferProtocol
.
payload
[
0
];
FileManager
::
Request
ackResponse
;
Q_ASSERT
(
requestFileTransferProtocol
.
target_system
==
_systemIdServer
);
mavlink_file_transfer_protocol_t
requestFTP
;
mavlink_msg_file_transfer_protocol_decode
(
&
message
,
&
requestFTP
);
if
(
requestFTP
.
target_system
!=
_systemIdServer
)
{
return
;
}
FileManager
::
Request
*
request
=
(
FileManager
::
Request
*
)
&
requestFTP
.
payload
[
0
];
uint16_t
incomingSeqNumber
=
request
->
hdr
.
seqNumber
;
uint16_t
outgoingSeqNumber
=
_nextSeqNumber
(
incomingSeqNumber
);
if
(
_errMode
==
errModeNoResponse
)
{
// Don't respond to any requests, this shold cause the client to eventually timeout waiting for the ack
return
;
}
else
if
(
_errMode
==
errModeNakResponse
)
{
// Nak all requests, the actual error send back doesn't really matter as long as it's an error
_sendNak
(
FileManager
::
kErrFail
,
outgoingSeqNumber
,
(
FileManager
::
Opcode
)
request
->
hdr
.
opcode
);
return
;
if
(
request
->
hdr
.
opcode
!=
FileManager
::
kCmdResetSessions
&&
request
->
hdr
.
opcode
!=
FileManager
::
kCmdTerminateSession
)
{
if
(
_errMode
==
errModeNoResponse
)
{
// Don't respond to any requests, this shold cause the client to eventually timeout waiting for the ack
return
;
}
else
if
(
_errMode
==
errModeNakResponse
)
{
// Nak all requests, the actual error send back doesn't really matter as long as it's an error
_sendNak
(
message
.
sysid
,
message
.
compid
,
FileManager
::
kErrFail
,
outgoingSeqNumber
,
(
FileManager
::
Opcode
)
request
->
hdr
.
opcode
);
return
;
}
}
switch
(
request
->
hdr
.
opcode
)
{
...
...
@@ -290,47 +305,47 @@ void MockMavlinkFileServer::sendMessage(mavlink_message_t message)
// ignored, ack not sent back, for testing only
break
;
case
FileManager
:
:
kCmdResetSessions
:
// terminates all sessions
// Fall through to send back Ack
case
FileManager
:
:
kCmdNone
:
// ignored, always acked
ackResponse
.
hdr
.
opcode
=
FileManager
::
kRspAck
;
ackResponse
.
hdr
.
session
=
0
;
ackResponse
.
hdr
.
size
=
0
;
_
emitResponse
(
&
ackResponse
,
outgoingSeqNumber
);
_
sendResponse
(
message
.
sysid
,
message
.
compid
,
&
ackResponse
,
outgoingSeqNumber
);
break
;
case
FileManager
:
:
kCmdListDirectory
:
_listCommand
(
request
,
incomingSeqNumber
);
_listCommand
(
message
.
sysid
,
message
.
compid
,
request
,
incomingSeqNumber
);
break
;
case
FileManager
:
:
kCmdOpenFileRO
:
_openCommand
(
request
,
incomingSeqNumber
);
_openCommand
(
message
.
sysid
,
message
.
compid
,
request
,
incomingSeqNumber
);
break
;
case
FileManager
:
:
kCmdReadFile
:
_readCommand
(
request
,
incomingSeqNumber
);
_readCommand
(
message
.
sysid
,
message
.
compid
,
request
,
incomingSeqNumber
);
break
;
case
FileManager
:
:
kCmdBurstReadFile
:
_streamCommand
(
request
,
incomingSeqNumber
);
_streamCommand
(
message
.
sysid
,
message
.
compid
,
request
,
incomingSeqNumber
);
break
;
case
FileManager
:
:
kCmdTerminateSession
:
_terminateCommand
(
request
,
incomingSeqNumber
);
_terminateCommand
(
message
.
sysid
,
message
.
compid
,
request
,
incomingSeqNumber
);
break
;
case
FileManager
:
:
kCmdResetSessions
:
_resetCommand
(
message
.
sysid
,
message
.
compid
,
incomingSeqNumber
);
break
;
default:
// nack for all NYI opcodes
_sendNak
(
FileManager
::
kErrUnknownCommand
,
outgoingSeqNumber
,
(
FileManager
::
Opcode
)
request
->
hdr
.
opcode
);
_sendNak
(
message
.
sysid
,
message
.
compid
,
FileManager
::
kErrUnknownCommand
,
outgoingSeqNumber
,
(
FileManager
::
Opcode
)
request
->
hdr
.
opcode
);
break
;
}
}
/// @brief Sends an Ack
void
Mock
MavlinkFileServer
::
_sendAck
(
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
)
void
Mock
LinkFileServer
::
_sendAck
(
uint8_t
targetSystemId
,
uint8_t
targetComponentId
,
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
)
{
FileManager
::
Request
ackResponse
;
...
...
@@ -339,11 +354,11 @@ void MockMavlinkFileServer::_sendAck(uint16_t seqNumber, FileManager::Opcode req
ackResponse
.
hdr
.
session
=
0
;
ackResponse
.
hdr
.
size
=
0
;
_
emitResponse
(
&
ackResponse
,
seqNumber
);
_
sendResponse
(
targetSystemId
,
targetComponentId
,
&
ackResponse
,
seqNumber
);
}
/// @brief Sends a Nak with the specified error code.
void
Mock
MavlinkFileServer
::
_sendNak
(
FileManager
::
ErrorCode
error
,
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
)
void
Mock
LinkFileServer
::
_sendNak
(
uint8_t
targetSystemId
,
uint8_t
targetComponentId
,
FileManager
::
ErrorCode
error
,
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
)
{
FileManager
::
Request
nakResponse
;
...
...
@@ -353,11 +368,11 @@ void MockMavlinkFileServer::_sendNak(FileManager::ErrorCode error, uint16_t seqN
nakResponse
.
hdr
.
size
=
1
;
nakResponse
.
data
[
0
]
=
error
;
_
emitResponse
(
&
nakResponse
,
seqNumber
);
_
sendResponse
(
targetSystemId
,
targetComponentId
,
&
nakResponse
,
seqNumber
);
}
/// @brief Emits a Request through the messageReceived signal.
void
Mock
MavlinkFileServer
::
_emitResponse
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
void
Mock
LinkFileServer
::
_sendResponse
(
uint8_t
targetSystemId
,
uint8_t
targetComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
)
{
mavlink_message_t
mavlinkMessage
;
...
...
@@ -367,16 +382,16 @@ void MockMavlinkFileServer::_emitResponse(FileManager::Request* request, uint16_
0
,
// Component ID
&
mavlinkMessage
,
// Mavlink Message to pack into
0
,
// Target network
_systemIdQGC
,
// QGC Target System ID
0
,
// Target component
targetSystemId
,
targetComponentId
,
(
uint8_t
*
)
request
);
// Payload
emit
messageReceived
(
NULL
,
mavlinkMessage
);
_mockLink
->
respondWithMavlinkMessage
(
mavlinkMessage
);
}
/// @brief Generates the next sequence number given an incoming sequence number. Handles generating
/// bad sequence numbers when errModeBadSequence is set.
uint16_t
Mock
Mavl
inkFileServer
::
_nextSeqNumber
(
uint16_t
seqNumber
)
uint16_t
Mock
L
inkFileServer
::
_nextSeqNumber
(
uint16_t
seqNumber
)
{
uint16_t
outgoingSeqNumber
=
seqNumber
+
1
;
...
...
src/
qgcunittest/MockMavl
inkFileServer.h
→
src/
comm/MockL
inkFileServer.h
View file @
bc71d49d
...
...
@@ -21,29 +21,25 @@
======================================================================*/
#ifndef MOCKMAVLINKFILESERVER_H
#define MOCKMAVLINKFILESERVER_H
#include "MockMavlinkInterface.h"
#include "FileManager.h"
/// @file
/// @brief Mock implementation of Mavlink FTP server. Used as mavlink plugin to MockUAS.
/// Only root directory access is supported.
///
/// @author Don Gagne <don@thegagnes.com>
#ifndef MockLinkFileServer_H
#define MockLinkFileServer_H
#include "FileManager.h"
#include <QStringList>
class
MockMavlinkFileServer
:
public
MockMavlinkInterface
class
MockLink
;
/// Mock implementation of Mavlink FTP server.
class
MockLinkFileServer
:
public
QObject
{
Q_OBJECT
public:
/// @brief Constructor for MockMavlinkFileServer
/// @param System ID for QGroundControl App
/// @pqram System ID for this Server
MockMavlinkFileServer
(
uint8_t
systemIdQGC
,
uint8_t
systemIdServer
);
MockLinkFileServer
(
uint8_t
systemIdServer
,
uint8_t
componentIdServer
,
MockLink
*
mockLink
);
/// @brief Sets the list of files returned by the List command. Prepend names with F or D
/// to indicate (F)ile or (D)irectory.
...
...
@@ -70,8 +66,8 @@ public:
/// @brief The number of ErrorModes in the rgFailureModes array.
static
const
size_t
cFailureModes
;
//
From MockMavlinkInterfac
e
v
irtual
void
sendMessage
(
mavlink_message_t
message
);
//
/ Called to handle an FTP messag
e
v
oid
handleFTPMessage
(
const
mavlink_message_t
&
message
);
/// @brief Used to represent a single test case for download testing.
struct
FileTestCase
{
...
...
@@ -88,18 +84,22 @@ public:
static
const
FileTestCase
rgFileTestCases
[
cFileTestCases
];
signals:
///
@brief
You can connect to this signal to be notified when the server receives a Terminate command.
/// You can connect to this signal to be notified when the server receives a Terminate command.
void
terminateCommandReceived
(
void
);
/// You can connect to this signal to be notified when the server receives a Reset command.
void
resetCommandReceived
(
void
);
private:
void
_sendAck
(
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
);
void
_sendNak
(
FileManager
::
ErrorCode
error
,
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
);
void
_emitResponse
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_listCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_openCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_readCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_streamCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_terminateCommand
(
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_sendAck
(
uint8_t
targetSystemId
,
uint8_t
targetComponentId
,
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
);
void
_sendNak
(
uint8_t
targetSystemId
,
uint8_t
targetComponentId
,
FileManager
::
ErrorCode
error
,
uint16_t
seqNumber
,
FileManager
::
Opcode
reqOpcode
);
void
_sendResponse
(
uint8_t
targetSystemId
,
uint8_t
targetComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_listCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_openCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_readCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_streamCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_terminateCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
FileManager
::
Request
*
request
,
uint16_t
seqNumber
);
void
_resetCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
uint16_t
seqNumber
);
uint16_t
_nextSeqNumber
(
uint16_t
seqNumber
);
QStringList
_fileList
;
///< List of files returned by List command
...
...
@@ -108,7 +108,8 @@ private:
uint8_t
_readFileLength
;
///< Length of active file being read
ErrorMode_t
_errMode
;
///< Currently set error mode, as specified by setErrorMode
const
uint8_t
_systemIdServer
;
///< System ID for server
const
uint8_t
_systemIdQGC
;
///< QGC System ID
const
uint8_t
_componentIdServer
;
///< Component ID for server
MockLink
*
_mockLink
;
///< MockLink to communicate through
};
#endif
src/qgcunittest/FileManagerTest.cc
View file @
bc71d49d
...
...
@@ -21,37 +21,21 @@
======================================================================*/
#include "FileManagerTest.h"
/// @file
/// @brief FileManager unit test. Note: All code here assumes all work between
/// the unit test, mack mavlink file server and file manager is happening on
/// the same thread.
///
/// @author Don Gagne <don@thegagnes.com>
#include "FileManagerTest.h"
#include "UASManager.h"
UT_REGISTER_TEST
(
FileManagerTest
)
FileManagerTest
::
FileManagerTest
(
void
)
:
_mockFileServer
(
_systemIdQGC
,
_systemIdServer
),
_mockLink
(
NULL
),
_fileServer
(
NULL
),
_fileManager
(
NULL
),
_multiSpy
(
NULL
)
{
}
// Called once before all test cases are run
void
FileManagerTest
::
initTestCase
(
void
)
{
_mockUAS
=
new
MockUAS
();
Q_CHECK_PTR
(
_mockUAS
);
_mockUAS
->
setMockSystemId
(
_systemIdServer
);
_mockUAS
->
setMockMavlinkPlugin
(
&
_mockFileServer
);
}
void
FileManagerTest
::
cleanupTestCase
(
void
)
{
delete
_mockUAS
;
}
// Called before every test case
...
...
@@ -59,26 +43,37 @@ void FileManagerTest::init(void)
{
UnitTest
::
init
();
Q_ASSERT
(
_multiSpy
==
NULL
);
_mockLink
=
new
MockLink
();
Q_CHECK_PTR
(
_mockLink
);
LinkManager
::
instance
()
->
_addLink
(
_mockLink
);
LinkManager
::
instance
()
->
connectLink
(
_mockLink
);
_fileServer
=
_mockLink
->
getFileServer
();
QVERIFY
(
_fileServer
!=
NULL
);
_fileManager
=
new
FileManager
(
NULL
,
_mockUAS
,
_systemIdQGC
);
Q_CHECK_PTR
(
_fileManager
);
// Wait or the UAS to show up
UASManagerInterface
*
uasManager
=
UASManager
::
instance
();
QSignalSpy
spyUasCreate
(
uasManager
,
SIGNAL
(
UASCreated
(
UASInterface
*
)));
if
(
!
uasManager
->
getActiveUAS
())
{
QCOMPARE
(
spyUasCreate
.
wait
(
10000
),
true
);
}
UASInterface
*
uas
=
uasManager
->
getActiveUAS
();
QVERIFY
(
uas
!=
NULL
);
_fileManager
=
uas
->
getFileManager
();
QVERIFY
(
_fileManager
!=
NULL
);
Q_ASSERT
(
_multiSpy
==
NULL
);
// Reset any internal state back to normal
_
mockFileServer
.
setErrorMode
(
MockMavl
inkFileServer
::
errModeNone
);
_
fileServer
->
setErrorMode
(
MockL
inkFileServer
::
errModeNone
);
_fileListReceived
.
clear
();
connect
(
&
_mockFileServer
,
&
MockMavlinkFileServer
::
messageReceived
,
_fileManager
,
&
FileManager
::
receiveMessage
);
connect
(
_fileManager
,
&
FileManager
::
listEntry
,
this
,
&
FileManagerTest
::
listEntry
);
_rgSignals
[
listEntrySignalIndex
]
=
SIGNAL
(
listEntry
(
const
QString
&
));
_rgSignals
[
listCompleteSignalIndex
]
=
SIGNAL
(
listComplete
(
void
));
_rgSignals
[
downloadFileLengthSignalIndex
]
=
SIGNAL
(
downloadFileLength
(
unsigned
int
));
_rgSignals
[
downloadFileCompleteSignalIndex
]
=
SIGNAL
(
downloadFileComplete
(
void
));
_rgSignals
[
errorMessageSignalIndex
]
=
SIGNAL
(
errorMessage
(
const
QString
&
));
_rgSignals
[
commandCompleteSignalIndex
]
=
SIGNAL
(
commandComplete
(
void
));
_rgSignals
[
commandErrorSignalIndex
]
=
SIGNAL
(
commandError
(
const
QString
&
));
_multiSpy
=
new
MultiSignalSpy
();
Q_CHECK_PTR
(
_multiSpy
);
...
...
@@ -91,10 +86,15 @@ void FileManagerTest::cleanup(void)
Q_ASSERT
(
_multiSpy
);
Q_ASSERT
(
_fileManager
);
delete
_fileManager
;
// Disconnecting the link will prompt for log file save
setExpectedFileDialog
(
getSaveFileName
,
QStringList
());
LinkManager
::
instance
()
->
disconnectLink
(
_mockLink
);
_fileServer
=
NULL
;
_mockLink
=
NULL
;
_fileManager
=
NULL
;
delete
_multiSpy
;
_fileManager
=
NULL
;
_multiSpy
=
NULL
;
UnitTest
::
cleanup
();
...
...
@@ -108,7 +108,6 @@ void FileManagerTest::listEntry(const QString& entry)
}
#if 0
void
FileManagerTest
::
_ackTest
(
void
)
{
Q_ASSERT
(
_fileManager
);
...
...
@@ -122,16 +121,17 @@ void FileManagerTest::_ackTest(void)
QVERIFY
(
_multiSpy
->
checkNoSignals
());
// Setup for no response from ack. This should cause a timeout error
_
mockFileServer.setErrorMode(MockMavl
inkFileServer::errModeNoResponse);
_
fileServer
->
setErrorMode
(
MockL
inkFileServer
::
errModeNoResponse
);
QVERIFY
(
_fileManager
->
_sendCmdTestAck
());
QTest::qWait(_ackTimerTimeoutMsecs); // Let the file manager timeout
QCOMPARE(_multiSpy->checkOnlySignalByMask(
errorMessage
SignalMask), true);
_multiSpy
->
waitForSignalByIndex
(
commandErrorSignalIndex
,
_ackTimerTimeoutMsecs
);
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
commandError
SignalMask
),
true
);
_multiSpy
->
clearAllSignals
();
// Setup for a bad sequence number in the ack. This should cause an error;
_
mockFileServer.setErrorMode(MockMavl
inkFileServer::errModeBadSequence);
_
fileServer
->
setErrorMode
(
MockL
inkFileServer
::
errModeBadSequence
);
QVERIFY
(
_fileManager
->
_sendCmdTestAck
());
QCOMPARE(_multiSpy->checkOnlySignalByMask(errorMessageSignalMask), true);
_multiSpy
->
waitForSignalByIndex
(
commandErrorSignalIndex
,
_ackTimerTimeoutMsecs
);
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
commandErrorSignalMask
),
true
);
_multiSpy
->
clearAllSignals
();
}
...
...
@@ -144,19 +144,7 @@ void FileManagerTest::_noAckTest(void)
// This should not get the ack back and timeout.
QVERIFY
(
_fileManager
->
_sendCmdTestNoAck
());
QTest
::
qWait
(
_ackTimerTimeoutMsecs
);
// Let the file manager timeout
QCOMPARE(_multiSpy->checkOnlySignalByMask(errorMessageSignalMask), true);
}
void FileManagerTest::_resetTest(void)
{
Q_ASSERT(_fileManager);
Q_ASSERT(_multiSpy);
Q_ASSERT(_multiSpy->checkNoSignals() == true);
// Send a reset command
// We should not get any signals back from this
QVERIFY(_fileManager->_sendCmdReset());
QVERIFY(_multiSpy->checkNoSignals());
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
commandErrorSignalMask
),
true
);
}
void
FileManagerTest
::
_listTest
(
void
)
...
...
@@ -167,37 +155,49 @@ void FileManagerTest::_listTest(void)
// FileManager::listDirectory signalling as follows:
// Emits a listEntry signal for each list entry
// Emits an
errorMessage
signal if:
// Emits an
commandError
signal if:
// It gets a Nak back
// Sequence number is incorrrect on any response
// CRC is incorrect on any responses
// List entry is formatted incorrectly
// It is possible to get a number of good listEntry signals, followed by an
errorMessage
signal
// Emits
list
Complete after it receives the final list entry
// If an
errorMessage
signal is signalled no listComplete is signalled
// It is possible to get a number of good listEntry signals, followed by an
commandError
signal
// Emits
command
Complete after it receives the final list entry
// If an
commandError
signal is signalled no listComplete is signalled
// Send a bogus path
// We should get a single resetStatusMessages signal
// We should get a single errorMessage signal
// We should get a single commandError signal
_fileManager
->
listDirectory
(
"/bogus"
);
QCOMPARE(_multiSpy->checkOnlySignalByMask(errorMessageSignalMask), true);
_multiSpy
->
waitForSignalByIndex
(
commandErrorSignalIndex
,
_ackTimerTimeoutMsecs
);
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
commandErrorSignalMask
),
true
);
_multiSpy
->
clearAllSignals
();
// Setup the mock file server with a valid directory list
QStringList
fileList
;
fileList
<<
"Ddir"
<<
"Ffoo"
<<
"Fbar"
;
_mockFileServer.setFileList(fileList);
_fileServer
->
setFileList
(
fileList
);
// Send a list command at the root of the directory tree which should succeed
_fileManager
->
listDirectory
(
"/"
);
QTest
::
qWait
(
_ackTimerTimeoutMsecs
);
// Let the file manager timeout
QCOMPARE
(
_multiSpy
->
checkSignalByMask
(
commandCompleteSignalMask
),
true
);
QCOMPARE
(
_multiSpy
->
checkNoSignalByMask
(
commandErrorSignalMask
),
true
);
QCOMPARE
(
_multiSpy
->
getSpyByIndex
(
listEntrySignalIndex
)
->
count
(),
fileList
.
count
());
QVERIFY
(
_fileListReceived
==
fileList
);
// Set everything back to initial state
_fileListReceived
.
clear
();
_multiSpy
->
clearAllSignals
();
// Run through the various server side failure modes
for (size_t i=0; i<Mock
Mavl
inkFileServer::cFailureModes; i++) {
Mock
MavlinkFileServer::ErrorMode_t errMode = MockMavl
inkFileServer::rgFailureModes[i];
for
(
size_t
i
=
0
;
i
<
Mock
L
inkFileServer
::
cFailureModes
;
i
++
)
{
Mock
LinkFileServer
::
ErrorMode_t
errMode
=
MockL
inkFileServer
::
rgFailureModes
[
i
];
qDebug
()
<<
"Testing failure mode:"
<<
errMode
;
_
mockFileServer.
setErrorMode(errMode);
_
fileServer
->
setErrorMode
(
errMode
);
_fileManager
->
listDirectory
(
"/"
);
QTest
::
qWait
(
_ackTimerTimeoutMsecs
);
// Let the file manager timeout
if (errMode == Mock
MavlinkFileServer::errModeNoSecondResponse || errMode == MockMavl
inkFileServer::errModeNakSecondResponse) {
if
(
errMode
==
Mock
LinkFileServer
::
errModeNoSecondResponse
||
errMode
==
MockL
inkFileServer
::
errModeNakSecondResponse
)
{
// For simulated server errors on subsequent Acks, the first Ack will go through. This means we should have gotten some
// partial results. In the case of the directory list test set, all entries fit into the first ack, so we should have
// gotten back all of them.
...
...
@@ -205,262 +205,193 @@ void FileManagerTest::_listTest(void)
_multiSpy
->
clearSignalByIndex
(
listEntrySignalIndex
);
// And then it should have errored out because the next list Request would have failed.
QCOMPARE(_multiSpy->checkOnlySignalByMask(
errorMessage
SignalMask), true);
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
commandError
SignalMask
),
true
);
}
else
{
// For the simulated errors which failed the intial response we should not have gotten any results back at all.
// Just an error.
QCOMPARE(_multiSpy->checkOnlySignalByMask(
errorMessage
SignalMask), true);
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
commandError
SignalMask
),
true
);
}
// Set everything back to initial state
_fileListReceived
.
clear
();
_multiSpy
->
clearAllSignals
();
_
mockFileServer.setErrorMode(MockMavl
inkFileServer::errModeNone);
_
fileServer
->
setErrorMode
(
MockL
inkFileServer
::
errModeNone
);
}
// Send a list command at the root of the directory tree which should succeed
_fileManager->listDirectory("/");
QCOMPARE(_multiSpy->checkSignalByMask(listCompleteSignalMask), true);
QCOMPARE(_multiSpy->checkNoSignalByMask(errorMessageSignalMask), true);
QCOMPARE(_multiSpy->getSpyByIndex(listEntrySignalIndex)->count(), fileList.count());
QVERIFY(_fileListReceived == fileList);
}
#if 0
// Trying to write test code for read and burst mode download as well as implement support in MockLineFileServer reached a point
// of diminishing returns where the test code and mock server were generating more bugs in themselves than finding problems.
void FileManagerTest::_readDownloadTest(void)
{
Q_ASSERT(_fileManager);
Q_ASSERT(_multiSpy);
Q_ASSERT(_multiSpy->checkNoSignals() == true);
// FileManager::downloadPath works as follows:
// Sends an Open Command to the server
// Expects an Ack Response back from the server with the correct sequence numner
// Emits an errorMessage signal if it gets a Nak back
// Emits an downloadFileLength signal with the file length if it gets back a good Ack
// Sends subsequent Read commands to the server until it gets the full file contents back
// Emits a downloadFileProgress for each read command ack it gets back
// Sends Terminate command to server when download is complete to close Open command
// Mock file server will signal terminateCommandReceived when it gets a Terminate command
// Sends downloadFileComplete signal to indicate the download is complete
// Emits an errorMessage signal if sequence number is incorrrect on any response
// Emits an errorMessage signal if CRC is incorrect on any responses
// Expected signals if the Open command fails for any reason
quint16 signalMaskOpenFailure = errorMessageSignalMask;
// Expected signals if the Read command fails for any reason
quint16 signalMaskReadFailure = downloadFileLengthSignalMask | errorMessageSignalMask;
// We setup a spy on the Reset command signal of the mock file server so that we can determine that a
// Reset command was correctly sent after the Open/Read commands complete.
QSignalSpy resetSpy(_fileServer, SIGNAL(resetCommandReceived()));
// Expected signals if the downloadPath command succeeds
quint16 signalMaskDownloadSuccess = downloadFileLengthSignalMask | downloadFileCompleteSignalMask;
// Send a bogus path
// We should get a single resetStatusMessages signal
// We should get a single errorMessage signal
_fileManager->downloadPath("bogus", QDir::temp());
QCOMPARE(_multiSpy->checkOnlySignalByMask(signalMaskOpenFailure), true);
_multiSpy->waitForSignalByIndex(commandErrorSignalIndex, _ackTimerTimeoutMsecs);
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandErrorSignalMask), true);
_multiSpy->clearAllSignals();
QCOMPARE(resetSpy.count(), 0);
// Clean previous downloads
for (size_t i=0; i<Mock
Mavl
inkFileServer::cFileTestCases; i++) {
QString filePath = QDir::temp().absoluteFilePath(Mock
Mavl
inkFileServer::rgFileTestCases[i].filename);
for (size_t i=0; i<Mock
L
inkFileServer::cFileTestCases; i++) {
QString filePath = QDir::temp().absoluteFilePath(Mock
L
inkFileServer::rgFileTestCases[i].filename);
if (QFile::exists(filePath)) {
Q_ASSERT(QFile::remove(filePath));
}
}
// We setup a spy on the Terminate command signal of the mock file server so that we can determine that a
// Terminate command was correctly sent after the Open/Read commands complete.
QSignalSpy terminateSpy(&_mockFileServer, SIGNAL(terminateCommandReceived()));
// Run through the set of file test cases
for (size_t i=0; i<Mock
Mavl
inkFileServer::cFileTestCases; i++) {
const Mock
MavlinkFileServer::FileTestCase* testCase = &MockMavl
inkFileServer::rgFileTestCases[i];
for (size_t i=0; i<Mock
L
inkFileServer::cFileTestCases; i++) {
const Mock
LinkFileServer::FileTestCase* testCase = &MockL
inkFileServer::rgFileTestCases[i];
// Run through the various failure modes for this test case
for (size_t j=0; j<MockMavlinkFileServer::cFailureModes; j++) {
for (size_t j=0; j<MockLinkFileServer::cFailureModes; j++) {
qDebug() << "Testing successful download";
MockMavlinkFileServer::ErrorMode_t errMode = MockMavlinkFileServer::rgFailureModes[j];
// Run what should be a successful file download test case. No servers errors are being simulated.
_fileServer->setErrorMode(MockLinkFileServer::errModeNone);
_fileManager->downloadPath(testCase->filename, QDir::temp());
QTest::qWait(_ackTimerTimeoutMsecs); // Let the file manager timeout
// This should be a succesful download
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandCompleteSignalMask), true);
_multiSpy->clearAllSignals();
// We should get a single Reset command to close the session
QCOMPARE(resetSpy.count(), 1);
resetSpy.clear();
// Validate file contents
QString filePath = QDir::temp().absoluteFilePath(MockLinkFileServer::rgFileTestCases[i].filename);
_validateFileContents(filePath, MockLinkFileServer::rgFileTestCases[i].length);
MockLinkFileServer::ErrorMode_t errMode = MockLinkFileServer::rgFailureModes[j];
qDebug() << "Testing failure mode:" << errMode;
_
mockFileServer.
setErrorMode(errMode);
_
fileServer->
setErrorMode(errMode);
_fileManager->downloadPath(testCase->filename, QDir::temp());
QTest::qWait(_ackTimerTimeoutMsecs); // Let the file manager timeout
if (errMode == MockMavlinkFileServer::errModeNoSecondResponse || errMode == MockMavlinkFileServer::errModeNakSecondResponse) {
// For simulated server errors on subsequent Acks, the first Ack will go through. We must handle things differently depending
// on whether the downloaded file requires multiple packets to complete the download.
if (testCase->fMultiPacketResponse) {
// The downloaded file requires multiple Acks to complete. Hence first Read should have succeeded and sent one downloadFileComplete.
// Second Read should have failed.
QCOMPARE(_multiSpy->checkOnlySignalByMask(signalMaskReadFailure), true);
// Open command succeeded, so we should get a Terminate for the open
QCOMPARE(terminateSpy.count(), 1);
} else {
if (errMode == MockLinkFileServer::errModeNakResponse) {
// This will Nak the Open call which will fail the download, but not cause a Reset
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandErrorSignalMask), true);
QCOMPARE(resetSpy.count(), 0);
} else {
if (testCase->packetCount == 1 && (errMode == MockLinkFileServer::errModeNoSecondResponse || errMode == MockLinkFileServer::errModeNakSecondResponse)) {
// The downloaded file fits within a single Ack response, hence there is no second Read issued.
// This should result in a successful download.
QCOMPARE(_multiSpy->checkOnlySignalByMask(signalMaskDownloadSuccess), true);
// We should get a single Terminate command to close the Open session
QCOMPARE(terminateSpy.count(), 1);
// This should result in a successful download, followed by a Reset
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandCompleteSignalMask), true);
QCOMPARE(resetSpy.count(), 1);
// Validate file contents
QString filePath = QDir::temp().absoluteFilePath(testCase->filename);
_validateFileContents(filePath, testCase->length);
} else {
// Download should have failed, followed by a aReset
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandErrorSignalMask), true);
QCOMPARE(resetSpy.count(), 1);
}
} else {
// For all the other simulated server errors the Open command should have failed. Since the Open failed
// there is no session to terminate, hence no Terminate in this case.
QCOMPARE(_multiSpy->checkOnlySignalByMask(signalMaskOpenFailure), true);
QCOMPARE(terminateSpy.count(), 0);
}
// Cleanup for next iteration
_multiSpy->clearAllSignals();
terminate
Spy.clear();
_
mockFileServer.setErrorMode(MockMavl
inkFileServer::errModeNone);
reset
Spy.clear();
_
fileServer->setErrorMode(MockL
inkFileServer::errModeNone);
}
// Run what should be a successful file download test case. No servers errors are being simulated.
_mockFileServer.setErrorMode(MockMavlinkFileServer::errModeNone);
_fileManager->downloadPath(testCase->filename, QDir::temp());
// This should be a succesful download
QCOMPARE(_multiSpy->checkOnlySignalByMask(signalMaskDownloadSuccess), true);
// Make sure the file length coming back through the openFileLength signal is correct
QVERIFY(_multiSpy->getSpyByIndex(downloadFileLengthSignalIndex)->takeFirst().at(0).toInt() == testCase->length);
_multiSpy->clearAllSignals();
// We should get a single Terminate command to close the session
QCOMPARE(terminateSpy.count(), 1);
terminateSpy.clear();
// Validate file contents
QString filePath = QDir::temp().absoluteFilePath(MockMavlinkFileServer::rgFileTestCases[i].filename);
_validateFileContents(filePath, MockMavlinkFileServer::rgFileTestCases[i].length);
}
}
#endif
void FileManagerTest::_streamDownloadTest(void)
{
Q_ASSERT
(
_fileManager
);
Q_ASSERT
(
_multiSpy
);
Q_ASSERT
(
_multiSpy
->
checkNoSignals
()
==
true
);
// FileManager::streamPath works as follows:
// Sends an Open Command to the server
// Expects an Ack Response back from the server with the correct sequence numner
// Emits an errorMessage signal if it gets a Nak back
// Emits an downloadFileLength signal with the file length if it gets back a good Ack
// Sends a single Stream command to the server
// Expects continuous Ack responses back with file contents
// Emits a downloadFileProgress for each ack it gets back
// Sends Terminate command to server when download is complete to close Open command
// Mock file server will signal terminateCommandReceived when it gets a Terminate command
// Sends downloadFileComplete signal to indicate the download is complete
// Emits an errorMessage signal if sequence number is incorrrect on any response
// Emits an errorMessage signal if CRC is incorrect on any responses
// Expected signals if the Open command fails for any reason
quint16
signalMaskOpenFailure
=
errorMessageSignalMask
;
// Expected signals if the Read command fails for any reason
quint16
signalMaskReadFailure
=
downloadFileLengthSignalMask
|
errorMessageSignalMask
;
// Expected signals if the downloadPath command succeeds
quint16
signalMaskDownloadSuccess
=
downloadFileLengthSignalMask
|
downloadFileCompleteSignalMask
;
// Send a bogus path
// We should get a single resetStatusMessages signal
// We should get a single errorMessage signal
_fileManager
->
streamPath
(
"bogus"
,
QDir
::
temp
());
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
signalMaskOpenFailure
),
true
);
_multiSpy
->
clearAllSignals
();
// Clean previous downloads
for
(
size_t
i
=
0
;
i
<
MockMavlinkFileServer
::
cFileTestCases
;
i
++
)
{
QString
filePath
=
QDir
::
temp
().
absoluteFilePath
(
MockMavlinkFileServer
::
rgFileTestCases
[
i
].
filename
);
if
(
QFile
::
exists
(
filePath
))
{
Q_ASSERT
(
QFile
::
remove
(
filePath
));
}
}
// We setup a spy on the Terminate command signal of the mock file server so that we can determine that a
// Terminate command was correctly sent after the Open/Read commands complete.
QSignalSpy
terminateSpy
(
&
_mockFileServer
,
SIGNAL
(
terminateCommandReceived
()));
// Run through the set of file test cases
for
(
size_t
i
=
0
;
i
<
MockMavlinkFileServer
::
cFileTestCases
;
i
++
)
{
const
MockMavlinkFileServer
::
FileTestCase
*
testCase
=
&
MockMavlinkFileServer
::
rgFileTestCases
[
i
];
// Run through the various failure modes for this test case
for
(
size_t
j
=
0
;
j
<
MockMavlinkFileServer
::
cFailureModes
;
j
++
)
{
MockMavlinkFileServer
::
ErrorMode_t
errMode
=
MockMavlinkFileServer
::
rgFailureModes
[
j
];
qDebug
()
<<
"Testing failure mode:"
<<
errMode
;
_mockFileServer
.
setErrorMode
(
errMode
);
_fileManager
->
streamPath
(
testCase
->
filename
,
QDir
::
temp
());
QTest
::
qWait
(
_ackTimerTimeoutMsecs
);
// Let the file manager timeout
if
(
errMode
==
MockMavlinkFileServer
::
errModeNoSecondResponse
||
errMode
==
MockMavlinkFileServer
::
errModeNakSecondResponse
)
{
// For simulated server errors on subsequent Acks, the first Ack will go through. We must handle things differently depending
// on whether the downloaded file requires multiple packets to complete the download.
if
(
testCase
->
packetCount
!=
1
)
{
// The downloaded file requires multiple Acks to complete. Second Ack should have failed.
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
signalMaskReadFailure
),
true
);
// Open command succeeded, so we should get a Terminate for the open
QCOMPARE
(
terminateSpy
.
count
(),
1
);
}
else
{
// The downloaded file fits within a single Ack response, hence there is no second Read issued.
// This should result in a successful download.
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
signalMaskDownloadSuccess
),
true
);
// We should get a single Terminate command to close the Open session
QCOMPARE
(
terminateSpy
.
count
(),
1
);
// Validate file contents
QString
filePath
=
QDir
::
temp
().
absoluteFilePath
(
testCase
->
filename
);
_validateFileContents
(
filePath
,
testCase
->
length
);
}
}
else
{
// For all the other simulated server errors the Open command should have failed. Since the Open failed
// there is no session to terminate, hence no Terminate in this case.
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
signalMaskOpenFailure
),
true
);
QCOMPARE
(
terminateSpy
.
count
(),
0
);
}
Q_ASSERT(_fileManager);
Q_ASSERT(_multiSpy);
Q_ASSERT(_multiSpy->checkNoSignals() == true);
// We setup a spy on the Reset command signal of the mock file server so that we can determine that a
// Reset command was correctly sent after the Open/Read commands complete.
QSignalSpy resetSpy(_fileServer, SIGNAL(resetCommandReceived()));
// Send a bogus path
_fileManager->streamPath("bogus", QDir::temp());
_multiSpy->waitForSignalByIndex(commandErrorSignalIndex, _ackTimerTimeoutMsecs);
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandErrorSignalMask), true);
_multiSpy->clearAllSignals();
QCOMPARE(resetSpy.count(), 0);
// Clean previous downloads
for (size_t i=0; i<MockLinkFileServer::cFileTestCases; i++) {
QString filePath = QDir::temp().absoluteFilePath(MockLinkFileServer::rgFileTestCases[i].filename);
if (QFile::exists(filePath)) {
Q_ASSERT(QFile::remove(filePath));
}
}
// Run through the set of file test cases
for (size_t i=0; i<MockLinkFileServer::cFileTestCases; i++) {
const MockLinkFileServer::FileTestCase* testCase = &MockLinkFileServer::rgFileTestCases[i];
// Run through the various failure modes for this test case
for (size_t j=0; j<MockLinkFileServer::cFailureModes; j++) {
qDebug() << "Testing successful download";
// Cleanup for next iteration
_multiSpy
->
clearAllSignals
();
terminateSpy
.
clear
();
_mockFileServer
.
setErrorMode
(
MockMavlinkFileServer
::
errModeNone
);
}
// Run what should be a successful file download test case. No servers errors are being simulated.
_mockFileServer
.
setErrorMode
(
MockMavlinkFileServer
::
errModeNone
);
_fileManager
->
streamPath
(
testCase
->
filename
,
QDir
::
temp
());
// This should be a succesful download
QCOMPARE
(
_multiSpy
->
checkOnlySignalByMask
(
signalMaskDownloadSuccess
),
true
);
// Make sure the file length coming back through the openFileLength signal is correct
QVERIFY
(
_multiSpy
->
getSpyByIndex
(
downloadFileLengthSignalIndex
)
->
takeFirst
().
at
(
0
).
toInt
()
==
testCase
->
length
);
_multiSpy
->
clearAllSignals
();
// We should get a single Terminate command to close the session
QCOMPARE
(
terminateSpy
.
count
(),
1
);
terminateSpy
.
clear
();
// Validate file contents
QString
filePath
=
QDir
::
temp
().
absoluteFilePath
(
MockMavlinkFileServer
::
rgFileTestCases
[
i
].
filename
);
_validateFileContents
(
filePath
,
MockMavlinkFileServer
::
rgFileTestCases
[
i
].
length
);
}
// Run what should be a successful file download test case. No servers errors are being simulated.
_fileServer->setErrorMode(MockLinkFileServer::errModeNone);
_fileManager->streamPath(testCase->filename, QDir::temp());
QTest::qWait(_ackTimerTimeoutMsecs); // Let the file manager timeout
// This should be a succesful download
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandCompleteSignalMask), true);
_multiSpy->clearAllSignals();
// We should get a single Reset command to close the session
QCOMPARE(resetSpy.count(), 1);
resetSpy.clear();
// Validate file contents
QString filePath = QDir::temp().absoluteFilePath(MockLinkFileServer::rgFileTestCases[i].filename);
_validateFileContents(filePath, MockLinkFileServer::rgFileTestCases[i].length);
MockLinkFileServer::ErrorMode_t errMode = MockLinkFileServer::rgFailureModes[j];
qDebug() << "Testing failure mode:" << errMode;
_fileServer->setErrorMode(errMode);
_fileManager->downloadPath(testCase->filename, QDir::temp());
QTest::qWait(_ackTimerTimeoutMsecs); // Let the file manager timeout
if (errMode == MockLinkFileServer::errModeNakResponse) {
// This will Nak the Open call which will fail the download, but not cause a Reset
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandErrorSignalMask), true);
QCOMPARE(resetSpy.count(), 0);
} else {
if (testCase->packetCount == 1 && (errMode == MockLinkFileServer::errModeNoSecondResponse || errMode == MockLinkFileServer::errModeNakSecondResponse)) {
// The downloaded file fits within a single Ack response, hence there is no second Read issued.
// This should result in a successful download, followed by a Reset
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandCompleteSignalMask), true);
QCOMPARE(resetSpy.count(), 1);
// Validate file contents
QString filePath = QDir::temp().absoluteFilePath(testCase->filename);
_validateFileContents(filePath, testCase->length);
} else {
// Download should have failed, followed by a aReset
QCOMPARE(_multiSpy->checkOnlySignalByMask(commandErrorSignalMask), true);
QCOMPARE(resetSpy.count(), 1);
}
}
// Cleanup for next iteration
_multiSpy->clearAllSignals();
resetSpy.clear();
_fileServer->setErrorMode(MockLinkFileServer::errModeNone);
}
}
}
void FileManagerTest::_validateFileContents(const QString& filePath, uint8_t length)
...
...
@@ -481,3 +412,4 @@ void FileManagerTest::_validateFileContents(const QString& filePath, uint8_t len
QCOMPARE((uint8_t)bytes[i], (uint8_t)(i & 0xFF));
}
}
#endif
src/qgcunittest/FileManagerTest.h
View file @
bc71d49d
...
...
@@ -28,9 +28,8 @@
#include <QtTest/QtTest>
#include "UnitTest.h"
#include "MockUAS.h"
#include "MockMavlinkFileServer.h"
#include "FileManager.h"
#include "MockLink.h"
#include "MultiSignalSpy.h"
/// @file
...
...
@@ -47,18 +46,13 @@ public:
private
slots
:
// Test case initialization
void
initTestCase
(
void
);
void
cleanupTestCase
(
void
);
void
init
(
void
);
void
cleanup
(
void
);
// Test cases
void
_ackTest
(
void
);
void
_noAckTest
(
void
);
void
_resetTest
(
void
);
void
_listTest
(
void
);
void
_readDownloadTest
(
void
);
void
_streamDownloadTest
(
void
);
// Connected to FileManager listEntry signal
void
listEntry
(
const
QString
&
entry
);
...
...
@@ -76,16 +70,15 @@ private:
enum
{
listEntrySignalMask
=
1
<<
listEntrySignalIndex
,
commandCompleteSignalMask
=
1
<<
commandCompleteSignalIndex
,
commandErrorSignalMask
=
1
<<
errorMessage
SignalIndex
,
commandErrorSignalMask
=
1
<<
commandError
SignalIndex
,
};
static
const
uint8_t
_systemIdQGC
=
255
;
static
const
uint8_t
_systemIdServer
=
128
;
MockUAS
*
_mockUAS
;
MockMavlinkFileServer
_mockFileServer
;
FileManager
*
_fileManager
;
MockLink
*
_mockLink
;
MockLinkFileServer
*
_fileServer
;
FileManager
*
_fileManager
;
MultiSignalSpy
*
_multiSpy
;
static
const
size_t
_cSignals
=
maxSignalIndex
;
...
...
src/qgcunittest/MockMavlinkInterface.cc
deleted
100644 → 0
View file @
886b40b5
//
// MockMavlinkInterface.cc
// QGroundControl
//
// Created by Donald Gagne on 6/19/14.
// Copyright (c) 2014 Donald Gagne. All rights reserved.
//
#include "MockMavlinkInterface.h"
src/qgcunittest/MockMavlinkInterface.h
deleted
100644 → 0
View file @
886b40b5
/*=====================================================================
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 <QObject>
#include "QGCMAVLink.h"
#include "LinkInterface.h"
#ifndef MOCKMAVLINKINTERFACE_H
#define MOCKMAVLINKINTERFACE_H
class
MockMavlinkInterface
:
public
QObject
{
Q_OBJECT
public:
virtual
void
sendMessage
(
mavlink_message_t
message
)
=
0
;
signals:
// link argument will always be NULL
void
messageReceived
(
LinkInterface
*
link
,
mavlink_message_t
message
);
};
#endif
src/uas/FileManager.cc
View file @
bc71d49d
...
...
@@ -32,13 +32,13 @@
QGC_LOGGING_CATEGORY
(
FileManagerLog
,
"FileManagerLog"
)
FileManager
::
FileManager
(
QObject
*
parent
,
UASInterface
*
uas
,
uint8_t
unitTestSystemIdQGC
)
:
FileManager
::
FileManager
(
QObject
*
parent
,
UASInterface
*
uas
)
:
QObject
(
parent
),
_currentOperation
(
kCOIdle
),
_mav
(
uas
),
_lastOutgoingSeqNumber
(
0
),
_activeSession
(
0
),
_systemIdQGC
(
unitTestSystemIdQGC
)
_systemIdQGC
(
0
)
{
connect
(
&
_ackTimer
,
&
QTimer
::
timeout
,
this
,
&
FileManager
::
_ackTimeout
);
...
...
@@ -104,8 +104,8 @@ void FileManager::_closeDownloadSession(bool success)
emit
commandComplete
();
}
// If !success error is emitted elsewhere
_readFileAccumulator
.
clear
();
// Close the open session
_sendResetCommand
();
}
...
...
@@ -153,24 +153,19 @@ void FileManager::_downloadAckResponse(Request* readAck, bool readFile)
emit
commandProgress
(
100
*
((
float
)
_readFileAccumulator
.
length
()
/
(
float
)
_downloadFileSize
));
}
if
(
readAck
->
hdr
.
size
==
sizeof
(
readAck
->
data
))
{
if
(
readFile
||
readAck
->
hdr
.
burstComplete
)
{
// Possibly still more data to read, send next read request
if
(
readFile
||
readAck
->
hdr
.
burstComplete
)
{
// Possibly still more data to read, send next read request
Request
request
;
request
.
hdr
.
session
=
_activeSession
;
request
.
hdr
.
opcode
=
readFile
?
kCmdReadFile
:
kCmdBurstReadFile
;
request
.
hdr
.
offset
=
_downloadOffset
;
request
.
hdr
.
size
=
0
;
Request
request
;
request
.
hdr
.
session
=
_activeSession
;
request
.
hdr
.
opcode
=
readFile
?
kCmdReadFile
:
kCmdBurstReadFile
;
request
.
hdr
.
offset
=
_downloadOffset
;
request
.
hdr
.
size
=
0
;
_sendRequest
(
&
request
);
}
else
{
// Streaming, so next ack should come automatically
_setupAckTimeout
();
}
}
else
if
(
readFile
)
{
// We only receieved a partial buffer back. These means we are at EOF
_closeDownloadSession
(
true
/* success */
);
_sendRequest
(
&
request
);
}
else
if
(
!
readFile
)
{
// Streaming, so next ack should come automatically
_setupAckTimeout
();
}
}
...
...
@@ -340,7 +335,30 @@ void FileManager::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Make sure we have a good sequence number
uint16_t
expectedSeqNumber
=
_lastOutgoingSeqNumber
+
1
;
if
(
incomingSeqNumber
!=
expectedSeqNumber
)
{
_currentOperation
=
kCOIdle
;
switch
(
_currentOperation
)
{
case
kCOBurst
:
case
kCORead
:
_closeDownloadSession
(
false
/* failure */
);
break
;
case
kCOWrite
:
_closeUploadSession
(
false
/* failure */
);
break
;
case
kCOOpenRead
:
case
kCOOpenBurst
:
case
kCOCreate
:
// We could have an open session hanging around
_currentOperation
=
kCOIdle
;
_sendResetCommand
();
break
;
default:
// Don't need to do anything special
_currentOperation
=
kCOIdle
;
break
;
}
_emitErrorMessage
(
tr
(
"Bad sequence number on received message: expected(%1) received(%2)"
).
arg
(
expectedSeqNumber
).
arg
(
incomingSeqNumber
));
return
;
}
...
...
@@ -457,12 +475,22 @@ void FileManager::_sendListCommand(void)
void
FileManager
::
downloadPath
(
const
QString
&
from
,
const
QDir
&
downloadDir
)
{
if
(
_currentOperation
!=
kCOIdle
)
{
_emitErrorMessage
(
tr
(
"Command not sent. Waiting for previous command to complete."
));
return
;
}
qCDebug
(
FileManagerLog
)
<<
"downloadPath from:"
<<
from
<<
"to:"
<<
downloadDir
;
_downloadWorker
(
from
,
downloadDir
,
true
/* read file */
);
}
void
FileManager
::
streamPath
(
const
QString
&
from
,
const
QDir
&
downloadDir
)
{
if
(
_currentOperation
!=
kCOIdle
)
{
_emitErrorMessage
(
tr
(
"Command not sent. Waiting for previous command to complete."
));
return
;
}
qCDebug
(
FileManagerLog
)
<<
"streamPath from:"
<<
from
<<
"to:"
<<
downloadDir
;
_downloadWorker
(
from
,
downloadDir
,
false
/* stream file */
);
}
...
...
@@ -677,7 +705,6 @@ void FileManager::_emitListEntry(const QString& entry)
/// @brief Sends the specified Request out to the UAS.
void
FileManager
::
_sendRequest
(
Request
*
request
)
{
qCDebug
(
FileManagerLog
)
<<
"_sendRequest opcode:"
<<
request
->
hdr
.
opcode
;
mavlink_message_t
message
;
...
...
@@ -687,6 +714,8 @@ void FileManager::_sendRequest(Request* request)
request
->
hdr
.
seqNumber
=
_lastOutgoingSeqNumber
;
qCDebug
(
FileManagerLog
)
<<
"_sendRequest opcode:"
<<
request
->
hdr
.
opcode
<<
"seqNumber:"
<<
request
->
hdr
.
seqNumber
;
if
(
_systemIdQGC
==
0
)
{
_systemIdQGC
=
MAVLinkProtocol
::
instance
()
->
getSystemId
();
}
...
...
src/uas/FileManager.h
View file @
bc71d49d
...
...
@@ -37,12 +37,11 @@ class FileManager : public QObject
Q_OBJECT
public:
FileManager
(
QObject
*
parent
,
UASInterface
*
uas
,
uint8_t
unitTestSystemIdQGC
=
0
);
FileManager
(
QObject
*
parent
,
UASInterface
*
uas
);
/// These methods are only used for testing purposes.
bool
_sendCmdTestAck
(
void
)
{
return
_sendOpcodeOnlyCmd
(
kCmdNone
,
kCOAck
);
};
bool
_sendCmdTestNoAck
(
void
)
{
return
_sendOpcodeOnlyCmd
(
kCmdTestNoAck
,
kCOAck
);
};
bool
_sendCmdReset
(
void
)
{
return
_sendOpcodeOnlyCmd
(
kCmdResetSessions
,
kCOAck
);
};
/// Timeout in msecs to wait for an Ack time come back. This is public so we can write unit tests which wait long enough
/// for the FileManager to timeout.
...
...
@@ -226,9 +225,9 @@ private:
uint8_t
_systemIdQGC
;
///< System ID for QGC
uint8_t
_systemIdServer
;
///< System ID for server
// We give Mock
Mavl
inkFileServer friend access so that it can use the data structures and opcodes
// We give Mock
L
inkFileServer friend access so that it can use the data structures and opcodes
// to build a mock mavlink file server for testing.
friend
class
Mock
Mavl
inkFileServer
;
friend
class
Mock
L
inkFileServer
;
};
#endif // FileManager_H
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