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
271ccccb
Commit
271ccccb
authored
Jun 30, 2020
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
d37c41b5
Changes
11
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
519 additions
and
375 deletions
+519
-375
FTPManager.cc
src/Vehicle/FTPManager.cc
+256
-181
FTPManager.h
src/Vehicle/FTPManager.h
+51
-34
FTPManagerTest.cc
src/Vehicle/FTPManagerTest.cc
+84
-0
FTPManagerTest.h
src/Vehicle/FTPManagerTest.h
+6
-2
LinkManager.cc
src/comm/LinkManager.cc
+4
-0
LinkManager.h
src/comm/LinkManager.h
+0
-4
MockLink.cc
src/comm/MockLink.cc
+2
-5
MockLink.h
src/comm/MockLink.h
+3
-3
MockLinkFTP.cc
src/comm/MockLinkFTP.cc
+99
-121
MockLinkFTP.h
src/comm/MockLinkFTP.h
+4
-16
UnitTest.cc
src/qgcunittest/UnitTest.cc
+10
-9
No files found.
src/Vehicle/FTPManager.cc
View file @
271ccccb
This diff is collapsed.
Click to expand it.
src/Vehicle/FTPManager.h
View file @
271ccccb
...
@@ -78,30 +78,30 @@ private slots:
...
@@ -78,30 +78,30 @@ private slots:
void
_ackTimeout
(
void
);
void
_ackTimeout
(
void
);
private:
private:
bool
_sendOpcodeOnlyCmd
(
MavlinkFTP
::
OpCode_t
opcode
,
MavlinkFTP
::
OpCode_t
newWaitState
);
bool
_sendOpcodeOnlyCmd
(
MavlinkFTP
::
OpCode_t
opcode
,
MavlinkFTP
::
OpCode_t
newWaitState
);
void
_setupAckTimeout
(
void
);
void
_emitErrorMessage
(
const
QString
&
msg
);
void
_clearAckTimeout
(
void
);
void
_emitListEntry
(
const
QString
&
entry
);
void
_emitErrorMessage
(
const
QString
&
msg
);
void
_sendRequestExpectAck
(
MavlinkFTP
::
Request
*
request
);
void
_emitListEntry
(
const
QString
&
entry
);
void
_sendRequestNoAck
(
MavlinkFTP
::
Request
*
request
);
void
_sendRequestExpectAck
(
MavlinkFTP
::
Request
*
request
);
void
_sendMessageOnLink
(
LinkInterface
*
link
,
mavlink_message_t
message
);
void
_sendRequestNoAck
(
MavlinkFTP
::
Request
*
request
);
void
_fillRequestWithString
(
MavlinkFTP
::
Request
*
request
,
const
QString
&
str
);
void
_sendMessageOnLink
(
LinkInterface
*
link
,
mavlink_message_t
message
);
void
_handlOpenFileROAck
(
MavlinkFTP
::
Request
*
ack
);
void
_fillRequestWithString
(
MavlinkFTP
::
Request
*
request
,
const
QString
&
str
);
void
_handleReadFileAck
(
MavlinkFTP
::
Request
*
ack
);
void
_handlOpenFileROAck
(
MavlinkFTP
::
Request
*
ack
);
void
_handleBurstReadFileAck
(
MavlinkFTP
::
Request
*
ack
);
void
_handleReadFileAck
(
MavlinkFTP
::
Request
*
ack
,
bool
burstReadFile
);
void
_listAckResponse
(
MavlinkFTP
::
Request
*
listAck
);
void
_listAckResponse
(
MavlinkFTP
::
Request
*
listAck
);
void
_createAckResponse
(
MavlinkFTP
::
Request
*
createAck
);
void
_createAckResponse
(
MavlinkFTP
::
Request
*
createAck
);
void
_writeAckResponse
(
MavlinkFTP
::
Request
*
writeAck
);
void
_writeAckResponse
(
MavlinkFTP
::
Request
*
writeAck
);
void
_writeFileDatablock
(
void
);
void
_writeFileDatablock
(
void
);
void
_sendListCommand
(
void
);
void
_sendListCommand
(
void
);
void
_sendResetCommand
(
void
);
void
_sendResetCommand
(
void
);
void
_downloadComplete
(
const
QString
&
errorMsg
);
void
_downloadComplete
(
const
QString
&
errorMsg
);
void
_uploadComplete
(
const
QString
&
errorMsg
);
void
_uploadComplete
(
const
QString
&
errorMsg
);
bool
_downloadWorker
(
const
QString
&
from
,
const
QString
&
toDir
);
bool
_downloadWorker
(
const
QString
&
from
,
const
QString
&
toDir
,
bool
burstReadFile
);
void
_requestMissingBurstData
(
void
);
void
_requestMissingData
(
void
);
void
_handleAck
(
MavlinkFTP
::
Request
*
ack
);
void
_handleNak
(
MavlinkFTP
::
Request
*
nak
);
MavlinkFTP
::
OpCode_t
_waitState
=
MavlinkFTP
::
kCmdNone
;
///< Current operation of state machine
MavlinkFTP
::
OpCode_t
_waitState
=
MavlinkFTP
::
kCmdNone
;
///< Current operation of state machine
MavlinkFTP
::
OpCode_t
_openFileType
=
MavlinkFTP
::
kCmdReadFile
;
///< Type of read to use after open file succeeds
QTimer
_ackTimer
;
///< Used to signal a timeout waiting for an ack
QTimer
_ackTimer
;
///< Used to signal a timeout waiting for an ack
int
_ackNumTries
;
///< current number of tries
int
_ackNumTries
;
///< current number of tries
Vehicle
*
_vehicle
;
Vehicle
*
_vehicle
;
...
@@ -117,17 +117,34 @@ private:
...
@@ -117,17 +117,34 @@ private:
uint32_t
_writeFileSize
;
///< Size of file being uploaded
uint32_t
_writeFileSize
;
///< Size of file being uploaded
QByteArray
_writeFileAccumulator
;
///< Holds file being uploaded
QByteArray
_writeFileAccumulator
;
///< Holds file being uploaded
struct
MissingData
{
typedef
struct
{
uint32_t
offset
;
uint32_t
offset
;
uint32_t
size
;
uint32_t
cBytes
;
};
}
MissingData_t
;
uint32_t
_requestedDownloadOffset
;
///< current download offset
QByteArray
_readFileAccumulator
;
///< Holds file being downloaded
struct
{
QDir
_readFileDownloadDir
;
///< Directory to download file to
uint32_t
expectedBurstOffset
;
///< offset which should be coming next in a burst sequence
QString
_readFileDownloadFilename
;
///< Filename (no path) for download file
uint32_t
expectedReadOffset
;
///< offset which should be coming from a hole filling read request
int
_downloadFileSize
;
///< Size of file being downloaded
uint32_t
bytesWritten
;
QList
<
MissingData_t
>
missingData
;
static
const
int
_ackTimerTimeoutMsecs
=
5000
;
QDir
toDir
;
///< Directory to download file to
static
const
int
_ackTimerMaxRetries
=
6
;
QString
fileName
;
///< Filename (no path) for download file
uint32_t
fileSize
;
///< Size of file being downloaded
QFile
file
;
int
retryCount
;
void
reset
()
{
expectedBurstOffset
=
0
;
expectedReadOffset
=
0
;
bytesWritten
=
0
;
retryCount
=
0
;
missingData
.
clear
();
file
.
close
();
}
}
_downloadState
;
static
const
int
_ackTimerTimeoutMsecs
=
1000
;
static
const
int
_ackTimerMaxRetries
=
6
;
static
const
int
_maxRetry
=
5
;
};
};
src/Vehicle/FTPManagerTest.cc
View file @
271ccccb
...
@@ -39,6 +39,48 @@ void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase)
...
@@ -39,6 +39,48 @@ void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase)
_disconnectMockLink
();
_disconnectMockLink
();
}
}
void
FTPManagerTest
::
_sizeTestCaseWorker
(
int
fileSize
)
{
_connectMockLinkNoInitialConnectSequence
();
FTPManager
*
ftpManager
=
_vehicle
->
ftpManager
();
QString
filename
=
QStringLiteral
(
"%1%2"
).
arg
(
MockLinkFTP
::
sizeFilenamePrefix
).
arg
(
fileSize
);
QSignalSpy
spyDownloadComplete
(
ftpManager
,
&
FTPManager
::
downloadComplete
);
ftpManager
->
download
(
filename
,
QStandardPaths
::
writableLocation
(
QStandardPaths
::
TempLocation
));
QCOMPARE
(
spyDownloadComplete
.
wait
(
10000
),
true
);
QCOMPARE
(
spyDownloadComplete
.
count
(),
1
);
// void downloadComplete (const QString& file, const QString& errorMsg);
QList
<
QVariant
>
arguments
=
spyDownloadComplete
.
takeFirst
();
QVERIFY
(
arguments
[
1
].
toString
().
isEmpty
());
_verifyFileSizeAndDelete
(
arguments
[
0
].
toString
(),
fileSize
);
_disconnectMockLink
();
}
void
FTPManagerTest
::
_performSizeBasedTestCases
(
void
)
{
// We test various boundary conditions on file sizes with respect to buffer sizes
const
QList
<
int
>
rgSizeTestCases
=
{
// File fits one Read Ack packet, partially filling data
sizeof
(((
MavlinkFTP
::
Request
*
)
0
)
->
data
)
-
1
,
// File fits one Read Ack packet, exactly filling all data
sizeof
(((
MavlinkFTP
::
Request
*
)
0
)
->
data
),
// File is larger than a single Read Ack packets, requires multiple Reads
sizeof
(((
MavlinkFTP
::
Request
*
)
0
)
->
data
)
+
1
,
// File is large enough to require multiple bursts
3
*
1024
,
};
for
(
int
fileSize
:
rgSizeTestCases
)
{
_sizeTestCaseWorker
(
fileSize
);
}
}
void
FTPManagerTest
::
_performTestCases
(
void
)
void
FTPManagerTest
::
_performTestCases
(
void
)
{
{
int
index
=
0
;
int
index
=
0
;
...
@@ -47,3 +89,45 @@ void FTPManagerTest::_performTestCases(void)
...
@@ -47,3 +89,45 @@ void FTPManagerTest::_performTestCases(void)
_testCaseWorker
(
testCase
);
_testCaseWorker
(
testCase
);
}
}
}
}
void
FTPManagerTest
::
_testLostPackets
(
void
)
{
_connectMockLinkNoInitialConnectSequence
();
FTPManager
*
ftpManager
=
_vehicle
->
ftpManager
();
int
fileSize
=
4
*
1024
;
QString
filename
=
QStringLiteral
(
"%1%2"
).
arg
(
MockLinkFTP
::
sizeFilenamePrefix
).
arg
(
fileSize
);
QSignalSpy
spyDownloadComplete
(
ftpManager
,
&
FTPManager
::
downloadComplete
);
_mockLink
->
mockLinkFTP
()
->
enableRandromDrops
(
true
);
ftpManager
->
download
(
filename
,
QStandardPaths
::
writableLocation
(
QStandardPaths
::
TempLocation
));
QCOMPARE
(
spyDownloadComplete
.
wait
(
10000
),
true
);
QCOMPARE
(
spyDownloadComplete
.
count
(),
1
);
// void downloadComplete (const QString& file, const QString& errorMsg);
QList
<
QVariant
>
arguments
=
spyDownloadComplete
.
takeFirst
();
QVERIFY
(
arguments
[
1
].
toString
().
isEmpty
());
_verifyFileSizeAndDelete
(
arguments
[
0
].
toString
(),
fileSize
);
_disconnectMockLink
();
}
void
FTPManagerTest
::
_verifyFileSizeAndDelete
(
const
QString
&
filename
,
int
expectedSize
)
{
QFileInfo
fileInfo
(
filename
);
QVERIFY
(
fileInfo
.
exists
());
QCOMPARE
(
fileInfo
.
size
(),
expectedSize
);
QFile
file
(
filename
);
QVERIFY
(
file
.
open
(
QFile
::
ReadOnly
));
for
(
int
i
=
0
;
i
<
expectedSize
;
i
++
)
{
QByteArray
bytes
=
file
.
read
(
1
);
QCOMPARE
(
bytes
[
0
],
(
char
)(
i
%
255
));
}
file
.
close
();
file
.
remove
();
}
src/Vehicle/FTPManagerTest.h
View file @
271ccccb
...
@@ -16,14 +16,18 @@ class FTPManagerTest : public UnitTest
...
@@ -16,14 +16,18 @@ class FTPManagerTest : public UnitTest
Q_OBJECT
Q_OBJECT
private
slots
:
private
slots
:
void
_performTestCases
(
void
);
void
_performSizeBasedTestCases
(
void
);
void
_performTestCases
(
void
);
void
_testLostPackets
(
void
);
private:
private:
typedef
struct
{
typedef
struct
{
const
char
*
file
;
const
char
*
file
;
}
TestCase_t
;
}
TestCase_t
;
void
_testCaseWorker
(
const
TestCase_t
&
testCase
);
void
_testCaseWorker
(
const
TestCase_t
&
testCase
);
void
_sizeTestCaseWorker
(
int
fileSize
);
void
_verifyFileSizeAndDelete
(
const
QString
&
filename
,
int
expectedSize
);
static
const
TestCase_t
_rgTestCases
[];
static
const
TestCase_t
_rgTestCases
[];
};
};
src/comm/LinkManager.cc
View file @
271ccccb
...
@@ -31,6 +31,10 @@
...
@@ -31,6 +31,10 @@
#include "PositionManager.h"
#include "PositionManager.h"
#endif
#endif
#ifdef QT_DEBUG
#include "MockLink.h"
#endif
QGC_LOGGING_CATEGORY
(
LinkManagerLog
,
"LinkManagerLog"
)
QGC_LOGGING_CATEGORY
(
LinkManagerLog
,
"LinkManagerLog"
)
QGC_LOGGING_CATEGORY
(
LinkManagerVerboseLog
,
"LinkManagerVerboseLog"
)
QGC_LOGGING_CATEGORY
(
LinkManagerVerboseLog
,
"LinkManagerVerboseLog"
)
...
...
src/comm/LinkManager.h
View file @
271ccccb
...
@@ -32,10 +32,6 @@
...
@@ -32,10 +32,6 @@
#include "SerialLink.h"
#include "SerialLink.h"
#endif
#endif
#ifdef QT_DEBUG
#include "MockLink.h"
#endif
Q_DECLARE_LOGGING_CATEGORY
(
LinkManagerLog
)
Q_DECLARE_LOGGING_CATEGORY
(
LinkManagerLog
)
Q_DECLARE_LOGGING_CATEGORY
(
LinkManagerVerboseLog
)
Q_DECLARE_LOGGING_CATEGORY
(
LinkManagerVerboseLog
)
...
...
src/comm/MockLink.cc
View file @
271ccccb
...
@@ -70,7 +70,6 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
...
@@ -70,7 +70,6 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
,
_vehicleLatitude
(
_defaultVehicleLatitude
+
((
_vehicleSystemId
-
128
)
*
0.0001
))
// Slight offset for each vehicle
,
_vehicleLatitude
(
_defaultVehicleLatitude
+
((
_vehicleSystemId
-
128
)
*
0.0001
))
// Slight offset for each vehicle
,
_vehicleLongitude
(
_defaultVehicleLongitude
+
((
_vehicleSystemId
-
128
)
*
0.0001
))
,
_vehicleLongitude
(
_defaultVehicleLongitude
+
((
_vehicleSystemId
-
128
)
*
0.0001
))
,
_vehicleAltitude
(
_defaultVehicleAltitude
)
,
_vehicleAltitude
(
_defaultVehicleAltitude
)
,
_fileServer
(
nullptr
)
,
_sendStatusText
(
false
)
,
_sendStatusText
(
false
)
,
_apmSendHomePositionOnEmptyList
(
false
)
,
_apmSendHomePositionOnEmptyList
(
false
)
,
_failureMode
(
MockConfiguration
::
FailNone
)
,
_failureMode
(
MockConfiguration
::
FailNone
)
...
@@ -96,8 +95,7 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
...
@@ -96,8 +95,7 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
px4_cm
.
main_mode
=
PX4_CUSTOM_MAIN_MODE_MANUAL
;
px4_cm
.
main_mode
=
PX4_CUSTOM_MAIN_MODE_MANUAL
;
_mavCustomMode
=
px4_cm
.
data
;
_mavCustomMode
=
px4_cm
.
data
;
_fileServer
=
new
MockLinkFTP
(
_vehicleSystemId
,
_vehicleComponentId
,
this
);
_mockLinkFTP
=
new
MockLinkFTP
(
_vehicleSystemId
,
_vehicleComponentId
,
this
);
Q_CHECK_PTR
(
_fileServer
);
moveToThread
(
this
);
moveToThread
(
this
);
...
@@ -899,8 +897,7 @@ void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
...
@@ -899,8 +897,7 @@ void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
void
MockLink
::
_handleFTP
(
const
mavlink_message_t
&
msg
)
void
MockLink
::
_handleFTP
(
const
mavlink_message_t
&
msg
)
{
{
Q_ASSERT
(
_fileServer
);
_mockLinkFTP
->
mavlinkMessageReceived
(
msg
);
_fileServer
->
handleFTPMessage
(
msg
);
}
}
void
MockLink
::
_handleCommandLong
(
const
mavlink_message_t
&
msg
)
void
MockLink
::
_handleCommandLong
(
const
mavlink_message_t
&
msg
)
...
...
src/comm/MockLink.h
View file @
271ccccb
...
@@ -119,7 +119,7 @@ public:
...
@@ -119,7 +119,7 @@ public:
/// Sends the specified mavlink message to QGC
/// Sends the specified mavlink message to QGC
void
respondWithMavlinkMessage
(
const
mavlink_message_t
&
msg
);
void
respondWithMavlinkMessage
(
const
mavlink_message_t
&
msg
);
MockLinkFTP
*
getFileServer
(
void
)
{
return
_fileServer
;
}
MockLinkFTP
*
mockLinkFTP
(
void
)
{
return
_mockLinkFTP
;
}
// Overrides from LinkInterface
// Overrides from LinkInterface
QString
getName
(
void
)
const
override
{
return
_name
;
}
QString
getName
(
void
)
const
override
{
return
_name
;
}
...
@@ -132,7 +132,7 @@ public:
...
@@ -132,7 +132,7 @@ public:
bool
connect
(
void
);
bool
connect
(
void
);
bool
disconnect
(
void
);
bool
disconnect
(
void
);
/// Sets a failure mode for unit testing
/// Sets a failure mode for unit testing
qgcm
/// @param failureMode Type of failure to simulate
/// @param failureMode Type of failure to simulate
/// @param failureAckResult Error to send if one the ack error modes
/// @param failureAckResult Error to send if one the ack error modes
void
setMissionItemFailureMode
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
,
MAV_MISSION_RESULT
failureAckResult
);
void
setMissionItemFailureMode
(
MockLinkMissionItemHandler
::
FailureMode_t
failureMode
,
MAV_MISSION_RESULT
failureAckResult
);
...
@@ -266,7 +266,7 @@ private:
...
@@ -266,7 +266,7 @@ private:
double
_vehicleLongitude
;
double
_vehicleLongitude
;
double
_vehicleAltitude
;
double
_vehicleAltitude
;
MockLinkFTP
*
_
fileServe
r
;
MockLinkFTP
*
_
mockLinkFTP
=
nullpt
r
;
bool
_sendStatusText
;
bool
_sendStatusText
;
bool
_apmSendHomePositionOnEmptyList
;
bool
_apmSendHomePositionOnEmptyList
;
...
...
src/comm/MockLinkFTP.cc
View file @
271ccccb
This diff is collapsed.
Click to expand it.
src/comm/MockLinkFTP.h
View file @
271ccccb
...
@@ -51,24 +51,12 @@ public:
...
@@ -51,24 +51,12 @@ public:
static
const
size_t
cFailureModes
;
static
const
size_t
cFailureModes
;
/// Called to handle an FTP message
/// Called to handle an FTP message
void
handleFTPMessage
(
const
mavlink_message_t
&
message
);
void
mavlinkMessageReceived
(
const
mavlink_message_t
&
message
);
/// @brief Used to represent a single test case for download testing.
struct
FileTestCase
{
const
char
*
filename
;
///< Filename to download
uint8_t
length
;
///< Length of file in bytes
int
packetCount
;
///< Number of packets required for data
bool
exactFit
;
///< true: last packet is exact fit, false: last packet is partially filled
};
/// @brief The numbers of test cases in the rgFileTestCases array.
static
const
size_t
cFileTestCases
=
3
;
/// @brief The set of files supported by the mock server for testing purposes. Each one represents a different edge case for testing.
static
const
FileTestCase
rgFileTestCases
[
cFileTestCases
];
void
enableRandromDrops
(
bool
enable
)
{
_randomDropsEnabled
=
enable
;
}
void
enableRandromDrops
(
bool
enable
)
{
_randomDropsEnabled
=
enable
;
}
static
const
char
*
sizeFilenamePrefix
;
signals:
signals:
/// 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
);
void
terminateCommandReceived
(
void
);
...
@@ -88,7 +76,7 @@ private:
...
@@ -88,7 +76,7 @@ private:
void
_terminateCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
MavlinkFTP
::
Request
*
request
,
uint16_t
seqNumber
);
void
_terminateCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
MavlinkFTP
::
Request
*
request
,
uint16_t
seqNumber
);
void
_resetCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
uint16_t
seqNumber
);
void
_resetCommand
(
uint8_t
senderSystemId
,
uint8_t
senderComponentId
,
uint16_t
seqNumber
);
uint16_t
_nextSeqNumber
(
uint16_t
seqNumber
);
uint16_t
_nextSeqNumber
(
uint16_t
seqNumber
);
QString
_createTest
CaseTempFile
(
const
FileTestCase
&
testCas
e
);
QString
_createTest
TempFile
(
int
siz
e
);
/// if request is a string, this ensures it's null-terminated
/// if request is a string, this ensures it's null-terminated
static
void
ensureNullTemination
(
MavlinkFTP
::
Request
*
request
);
static
void
ensureNullTemination
(
MavlinkFTP
::
Request
*
request
);
...
...
src/qgcunittest/UnitTest.cc
View file @
271ccccb
...
@@ -19,6 +19,7 @@
...
@@ -19,6 +19,7 @@
#include "Vehicle.h"
#include "Vehicle.h"
#include "AppSettings.h"
#include "AppSettings.h"
#include "SettingsManager.h"
#include "SettingsManager.h"
#include "MockLink.h"
#include <QRandomGenerator>
#include <QRandomGenerator>
#include <QTemporaryFile>
#include <QTemporaryFile>
...
@@ -36,15 +37,15 @@ enum UnitTest::FileDialogType UnitTest::_fileDialogExpectedType = getOpenFileNam
...
@@ -36,15 +37,15 @@ enum UnitTest::FileDialogType UnitTest::_fileDialogExpectedType = getOpenFileNam
int
UnitTest
::
_missedFileDialogCount
=
0
;
int
UnitTest
::
_missedFileDialogCount
=
0
;
UnitTest
::
UnitTest
(
void
)
UnitTest
::
UnitTest
(
void
)
:
_linkManager
(
nullptr
)
:
_linkManager
(
nullptr
)
,
_mockLink
(
nullptr
)
,
_mockLink
(
nullptr
)
,
_mainWindow
(
nullptr
)
,
_mainWindow
(
nullptr
)
,
_vehicle
(
nullptr
)
,
_vehicle
(
nullptr
)
,
_expectMissedFileDialog
(
false
)
,
_expectMissedFileDialog
(
false
)
,
_expectMissedMessageBox
(
false
)
,
_expectMissedMessageBox
(
false
)
,
_unitTestRun
(
false
)
,
_unitTestRun
(
false
)
,
_initCalled
(
false
)
,
_initCalled
(
false
)
,
_cleanupCalled
(
false
)
,
_cleanupCalled
(
false
)
{
{
}
}
...
...
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