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
1b9e036e
Commit
1b9e036e
authored
Apr 15, 2017
by
Don Gagne
Committed by
GitHub
Apr 15, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4995 from DonLakeFlyer/UTFixes
Unit test fixes
parents
dccb2368
e72dd961
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
116 additions
and
75 deletions
+116
-75
MissionCommandUIInfo.cc
src/MissionManager/MissionCommandUIInfo.cc
+2
-2
MissionCommandUIInfo.h
src/MissionManager/MissionCommandUIInfo.h
+1
-1
MissionControllerManagerTest.cc
src/MissionManager/MissionControllerManagerTest.cc
+1
-1
MissionControllerTest.cc
src/MissionManager/MissionControllerTest.cc
+31
-30
MissionControllerTest.h
src/MissionManager/MissionControllerTest.h
+6
-6
MissionItemTest.cc
src/MissionManager/MissionItemTest.cc
+20
-3
MissionItemTest.h
src/MissionManager/MissionItemTest.h
+6
-1
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+43
-30
SimpleMissionItemTest.h
src/MissionManager/SimpleMissionItemTest.h
+6
-1
No files found.
src/MissionManager/MissionCommandUIInfo.cc
View file @
1b9e036e
...
...
@@ -358,9 +358,9 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
paramInfo
->
_nanUnchanged
=
paramObject
.
value
(
_nanUnchangedJsonKey
).
toBool
(
false
);
if
(
paramObject
.
contains
(
_defaultJsonKey
))
{
paramInfo
->
_defaultValue
=
paramObject
.
value
(
_defaultJsonKey
).
toDouble
(
0.0
);
paramInfo
->
_defaultValue
=
paramObject
.
value
(
_defaultJsonKey
).
toDouble
(
0.0
);
}
else
{
paramInfo
->
_defaultValue
=
_nanUnchangedJsonKey
?
std
::
numeric_limits
<
double
>::
quiet_NaN
()
:
0
;
paramInfo
->
_defaultValue
=
paramInfo
->
_nanUnchanged
?
std
::
numeric_limits
<
double
>::
quiet_NaN
()
:
0
;
}
QStringList
enumValues
=
paramObject
.
value
(
_enumValuesJsonKey
).
toString
().
split
(
","
,
QString
::
SkipEmptyParts
);
...
...
src/MissionManager/MissionCommandUIInfo.h
View file @
1b9e036e
...
...
@@ -31,7 +31,7 @@ class MissionCommandTreeTest;
/// Key Type Default Description
/// label string required Label for text field
/// units string Units for value, should use FactMetaData units strings in order to get automatic translation
/// default double 0.0/NaN Default value for param. If no default value specified and nanUnchanged == true, then defaultVlue is NaN.
/// default double 0.0/NaN Default value for param. If no default value specified and nanUnchanged == true, then defaultV
a
lue is NaN.
/// decimalPlaces int 7 Number of decimal places to show for value
/// enumStrings string Strings to show in combo box for selection
/// enumValues string Values assocaited with each enum string
...
...
src/MissionManager/MissionControllerManagerTest.cc
View file @
1b9e036e
...
...
@@ -35,7 +35,7 @@ void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareTy
_missionManager
=
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
missionManager
();
QVERIFY
(
_missionManager
);
_rgMissionManagerSignals
[
newMissionItemsAvailableSignalIndex
]
=
SIGNAL
(
newMissionItemsAvailable
(
void
));
_rgMissionManagerSignals
[
newMissionItemsAvailableSignalIndex
]
=
SIGNAL
(
newMissionItemsAvailable
(
bool
));
_rgMissionManagerSignals
[
inProgressChangedSignalIndex
]
=
SIGNAL
(
inProgressChanged
(
bool
));
_rgMissionManagerSignals
[
errorSignalIndex
]
=
SIGNAL
(
error
(
int
,
const
QString
&
));
...
...
src/MissionManager/MissionControllerTest.cc
View file @
1b9e036e
...
...
@@ -12,6 +12,7 @@
#include "LinkManager.h"
#include "MultiVehicleManager.h"
#include "SimpleMissionItem.h"
#include "MissionSettingsItem.h"
MissionControllerTest
::
MissionControllerTest
(
void
)
:
_multiSpyMissionController
(
NULL
)
...
...
@@ -41,13 +42,8 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
MissionControllerManagerTest
::
_initForFirmwareType
(
firmwareType
);
void
coordinateChanged
(
const
QGeoCoordinate
&
coordinate
);
void
headingDegreesChanged
(
double
heading
);
void
dirtyChanged
(
bool
dirty
);
void
homePositionValidChanged
(
bool
homePostionValid
);
// MissionItem signals
_rgMissionItemSignals
[
coordinateChangedSignalIndex
]
=
SIGNAL
(
coordinateChanged
(
const
QGeoCoordinate
&
));
// VisualMissionItem signals
_rgVisualItemSignals
[
coordinateChangedSignalIndex
]
=
SIGNAL
(
coordinateChanged
(
const
QGeoCoordinate
&
));
// MissionController signals
_rgMissionControllerSignals
[
visualItemsChangedSignalIndex
]
=
SIGNAL
(
visualItemsChanged
());
...
...
@@ -64,7 +60,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
QCOMPARE
(
_multiSpyMissionController
->
init
(
_missionController
,
_rgMissionControllerSignals
,
_cMissionControllerSignals
),
true
);
if
(
startController
)
{
_missionController
->
start
(
fals
e
/* editMode */
);
_missionController
->
start
(
tru
e
/* editMode */
);
}
// All signals should some through on start
...
...
@@ -77,13 +73,15 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
// Empty vehicle only has home position
QCOMPARE
(
visualItems
->
count
(),
1
);
// Home position should be in first slot, but not yet valid
SimpleMissionItem
*
homeItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItems
->
get
(
0
));
QVERIFY
(
homeItem
);
QCOMPARE
(
homeItem
->
homePosition
(),
true
);
// Mission Settings should be in first slot
MissionSettingsItem
*
settingsItem
=
visualItems
->
value
<
MissionSettingsItem
*>
(
0
);
QVERIFY
(
settingsItem
);
// Offline vehicle, so no home position
QCOMPARE
(
settingsItem
->
coordinate
().
isValid
(),
false
);
//
Home should have no children
QCOMPARE
(
home
Item
->
childItems
()
->
count
(),
0
);
//
Empty mission, so no child items possible
QCOMPARE
(
settings
Item
->
childItems
()
->
count
(),
0
);
// No waypoint lines
QmlObjectListModel
*
waypointLines
=
_missionController
->
waypointLines
();
...
...
@@ -100,10 +98,10 @@ void MissionControllerTest::_testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType)
QmlObjectListModel
*
visualItems
=
_missionController
->
visualItems
();
QVERIFY
(
visualItems
);
SimpleMissionItem
*
homeItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItems
->
get
(
0
)
);
QVERIFY
(
home
Item
);
VisualMissionItem
*
visualItem
=
visualItems
->
value
<
VisualMissionItem
*>
(
0
);
QVERIFY
(
visual
Item
);
_setup
MissionItemSignals
(
home
Item
);
_setup
VisualItemSignals
(
visual
Item
);
}
void
MissionControllerTest
::
_testEmptyVehiclePX4
(
void
)
...
...
@@ -131,23 +129,26 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QCOMPARE
(
visualItems
->
count
(),
2
);
SimpleMissionItem
*
homeItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItems
->
get
(
0
)
);
SimpleMissionItem
*
item
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItems
->
get
(
1
)
);
QVERIFY
(
home
Item
);
QVERIFY
(
i
tem
);
MissionSettingsItem
*
settingsItem
=
visualItems
->
value
<
MissionSettingsItem
*>
(
0
);
SimpleMissionItem
*
simpleItem
=
visualItems
->
value
<
SimpleMissionItem
*>
(
1
);
QVERIFY
(
settings
Item
);
QVERIFY
(
simpleI
tem
);
QCOMPARE
(
item
->
command
(),
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
);
QCOMPARE
(
homeItem
->
childItems
()
->
count
(),
firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
?
1
:
0
);
QCOMPARE
(
item
->
childItems
()
->
count
(),
0
);
QCOMPARE
(
simpleItem
->
command
(),
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
);
QCOMPARE
(
simpleItem
->
childItems
()
->
count
(),
0
);
#if 0
// This needs re-work
int expectedLineCount = firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : 1
;
// If the first item added specifies a coordinate, then planned home position will be set
bool
plannedHomePositionValue
=
firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
?
false
:
true
;
QCOMPARE
(
settingsItem
->
coordinate
().
isValid
(),
plannedHomePositionValue
)
;
// ArduPilot takeoff command has no coordinate, so should be child item
QCOMPARE
(
settingsItem
->
childItems
()
->
count
(),
firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
?
1
:
0
);
// Check waypoint line from home to takeoff
int
expectedLineCount
=
firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
?
0
:
1
;
QmlObjectListModel
*
waypointLines
=
_missionController
->
waypointLines
();
QVERIFY
(
waypointLines
);
QCOMPARE
(
waypointLines
->
count
(),
expectedLineCount
);
#endif
}
void
MissionControllerTest
::
_testAddWayppointAPM
(
void
)
...
...
@@ -191,11 +192,11 @@ void MissionControllerTest::_testOfflineToOnlinePX4(void)
_testOfflineToOnlineWorker
(
MAV_AUTOPILOT_PX4
);
}
void
MissionControllerTest
::
_setup
MissionItemSignals
(
SimpleMissionItem
*
i
tem
)
void
MissionControllerTest
::
_setup
VisualItemSignals
(
VisualMissionItem
*
visualI
tem
)
{
delete
_multiSpyMissionItem
;
_multiSpyMissionItem
=
new
MultiSignalSpy
();
Q_CHECK_PTR
(
_multiSpyMissionItem
);
QCOMPARE
(
_multiSpyMissionItem
->
init
(
item
,
_rgMissionItemSignals
,
_cMission
ItemSignals
),
true
);
QCOMPARE
(
_multiSpyMissionItem
->
init
(
visualItem
,
_rgVisualItemSignals
,
_cVisual
ItemSignals
),
true
);
}
src/MissionManager/MissionControllerTest.h
View file @
1b9e036e
...
...
@@ -43,18 +43,18 @@ private:
void
_testEmptyVehicleWorker
(
MAV_AUTOPILOT
firmwareType
);
void
_testAddWaypointWorker
(
MAV_AUTOPILOT
firmwareType
);
void
_testOfflineToOnlineWorker
(
MAV_AUTOPILOT
firmwareType
);
void
_setup
MissionItemSignals
(
SimpleMissionItem
*
i
tem
);
void
_setup
VisualItemSignals
(
VisualMissionItem
*
visualI
tem
);
// MissiomItems signals
enum
{
coordinateChangedSignalIndex
=
0
,
mission
ItemMaxSignalIndex
visual
ItemMaxSignalIndex
};
enum
{
coordinateChangedSignalMask
=
1
<<
coordinateChangedSignalIndex
,
missionItemMaxSignalMask
=
1
<<
mission
ItemMaxSignalIndex
,
coordinateChangedSignalMask
=
1
<<
coordinateChangedSignalIndex
,
visualItemMaxSignalMask
=
1
<<
visual
ItemMaxSignalIndex
,
};
// MissionController signals
...
...
@@ -75,8 +75,8 @@ private:
const
char
*
_rgMissionControllerSignals
[
_cMissionControllerSignals
];
MultiSignalSpy
*
_multiSpyMissionItem
;
static
const
size_t
_c
MissionItemSignals
=
mission
ItemMaxSignalIndex
;
const
char
*
_rg
MissionItemSignals
[
_cMission
ItemSignals
];
static
const
size_t
_c
VisualItemSignals
=
visual
ItemMaxSignalIndex
;
const
char
*
_rg
VisualItemSignals
[
_cVisual
ItemSignals
];
MissionController
*
_missionController
;
};
...
...
src/MissionManager/MissionItemTest.cc
View file @
1b9e036e
...
...
@@ -13,6 +13,7 @@
#include "MultiVehicleManager.h"
#include "MissionItem.h"
#include "SimpleMissionItem.h"
#include "QGCApplication.h"
#if 0
const MissionItemTest::TestCase_t MissionItemTest::_rgTestCases[] = {
...
...
@@ -27,8 +28,24 @@ const size_t MissionItemTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestC
#endif
MissionItemTest
::
MissionItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
{
}
void
MissionItemTest
::
init
(
void
)
{
UnitTest
::
init
();
_offlineVehicle
=
new
Vehicle
(
MAV_AUTOPILOT_PX4
,
MAV_TYPE_QUADROTOR
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
(),
this
);
}
void
MissionItemTest
::
cleanup
(
void
)
{
delete
_offlineVehicle
;
UnitTest
::
cleanup
();
}
// Test property get/set
...
...
@@ -255,7 +272,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem
simpleMissionItem
(
NULL
);
SimpleMissionItem
simpleMissionItem
(
_offlineVehicle
);
QString
testString
(
"10
\t
0
\t
3
\t
80
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
);
QTextStream
testStream
(
&
testString
,
QIODevice
::
ReadOnly
);
...
...
@@ -395,7 +412,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem
simpleMissionItem
(
NULL
);
SimpleMissionItem
simpleMissionItem
(
_offlineVehicle
);
QString
errorString
;
QJsonArray
coordinateArray
;
QJsonObject
jsonObject
;
...
...
src/MissionManager/MissionItemTest.h
View file @
1b9e036e
...
...
@@ -14,6 +14,7 @@
#include "UnitTest.h"
#include "MultiSignalSpy.h"
#include "MissionItem.h"
#include "Vehicle.h"
/// Unit test for the MissionItem Object
class
MissionItemTest
:
public
UnitTest
...
...
@@ -23,6 +24,9 @@ class MissionItemTest : public UnitTest
public:
MissionItemTest
(
void
);
void
init
(
void
)
override
;
void
cleanup
(
void
)
override
;
private
slots
:
void
_testSetGet
(
void
);
void
_testSignals
(
void
);
...
...
@@ -37,7 +41,8 @@ private slots:
private:
void
_checkExpectedMissionItem
(
const
MissionItem
&
missionItem
);
int
_seq
=
10
;
int
_seq
=
10
;
Vehicle
*
_offlineVehicle
;
};
#endif
src/MissionManager/SimpleMissionItemTest.cc
View file @
1b9e036e
...
...
@@ -26,43 +26,43 @@ const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = {
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesWaypoint
[]
=
{
{
"Altitude
:"
,
70.1234567
},
{
"Hold
:"
,
10.1234567
},
{
"Altitude
"
,
70.1234567
},
{
"Hold
"
,
10.1234567
},
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesLoiterUnlim
[]
=
{
{
"Altitude
:"
,
70.1234567
},
{
"Radius
:"
,
30.1234567
},
{
"Altitude
"
,
70.1234567
},
{
"Radius
"
,
30.1234567
},
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesLoiterTurns
[]
=
{
{
"Altitude
:"
,
70.1234567
},
{
"Radius
:"
,
30.1234567
},
{
"Turns
:"
,
10.1234567
},
{
"Altitude
"
,
70.1234567
},
{
"Radius
"
,
30.1234567
},
{
"Turns
"
,
10.1234567
},
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesLoiterTime
[]
=
{
{
"Altitude
:"
,
70.1234567
},
{
"Radius
:"
,
30.1234567
},
{
"Hold
:"
,
10.1234567
},
{
"Altitude
"
,
70.1234567
},
{
"Radius
"
,
30.1234567
},
{
"Hold
"
,
10.1234567
},
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesLand
[]
=
{
{
"Altitude
:"
,
70.1234567
},
{
"Altitude
"
,
70.1234567
},
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesTakeoff
[]
=
{
{
"Pitch
:"
,
10.1234567
},
{
"Altitude
:"
,
70.1234567
},
{
"Pitch
"
,
10.1234567
},
{
"Altitude
"
,
70.1234567
},
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesConditionDelay
[]
=
{
{
"Hold
:"
,
10.1234567
},
{
"Hold
"
,
10.1234567
},
};
const
SimpleMissionItemTest
::
FactValue_t
SimpleMissionItemTest
::
_rgFactValuesDoJump
[]
=
{
{
"Item #
:"
,
10.1234567
},
{
"Repeat
:"
,
20.1234567
},
{
"Item #
"
,
10.1234567
},
{
"Repeat
"
,
20.1234567
},
};
const
SimpleMissionItemTest
::
ItemExpected_t
SimpleMissionItemTest
::
_rgItemExpected
[]
=
{
...
...
@@ -77,10 +77,27 @@ const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpect
};
SimpleMissionItemTest
::
SimpleMissionItemTest
(
void
)
:
_offlineVehicle
(
NULL
)
{
}
void
SimpleMissionItemTest
::
init
(
void
)
{
UnitTest
::
init
();
_offlineVehicle
=
new
Vehicle
(
MAV_AUTOPILOT_PX4
,
MAV_TYPE_QUADROTOR
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
(),
this
);
}
void
SimpleMissionItemTest
::
cleanup
(
void
)
{
delete
_offlineVehicle
;
UnitTest
::
cleanup
();
}
void
SimpleMissionItemTest
::
_testEditorFacts
(
void
)
{
Vehicle
*
vehicle
=
new
Vehicle
(
MAV_AUTOPILOT_PX4
,
MAV_TYPE_FIXED_WING
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
());
...
...
@@ -89,7 +106,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
const
ItemInfo_t
*
info
=
&
_rgItemInfo
[
i
];
const
ItemExpected_t
*
expected
=
&
_rgItemExpected
[
i
];
qDebug
()
<<
"Command
:
"
<<
info
->
command
;
qDebug
()
<<
"Command"
<<
info
->
command
;
MissionItem
missionItem
(
1
,
// sequence number
info
->
command
,
...
...
@@ -137,7 +154,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
void
SimpleMissionItemTest
::
_testDefaultValues
(
void
)
{
SimpleMissionItem
item
(
NULL
/* Vehicle */
);
SimpleMissionItem
item
(
_offlineVehicle
);
item
.
missionItem
().
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
item
.
missionItem
().
setFrame
(
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
...
...
@@ -148,27 +165,25 @@ void SimpleMissionItemTest::_testSignals(void)
{
enum
{
commandChangedIndex
=
0
,
coordinateChangedIndex
,
exitCoordinateChangedIndex
,
dirtyChangedIndex
,
frameChangedIndex
,
friendlyEditAllowedChangedIndex
,
headingDegreesChangedIndex
,
rawEditChangedIndex
,
uiModelChangedIndex
,
coordinateChangedIndex
,
exitCoordinateChangedIndex
,
dirtyChangedIndex
,
maxSignalIndex
};
enum
{
commandChangedMask
=
1
<<
commandChangedIndex
,
coordinateChangedMask
=
1
<<
coordinateChangedIndex
,
exitCoordinateChangedMask
=
1
<<
exitCoordinateChangedIndex
,
dirtyChangedMask
=
1
<<
dirtyChangedIndex
,
frameChangedMask
=
1
<<
frameChangedIndex
,
friendlyEditAllowedChangedMask
=
1
<<
friendlyEditAllowedChangedIndex
,
headingDegreesChangedMask
=
1
<<
headingDegreesChangedIndex
,
rawEditChangedMask
=
1
<<
rawEditChangedIndex
,
uiModelChangedMask
=
1
<<
uiModelChangedIndex
,
coordinateChangedMask
=
1
<<
coordinateChangedIndex
,
exitCoordinateChangedMask
=
1
<<
exitCoordinateChangedIndex
,
dirtyChangedMask
=
1
<<
dirtyChangedIndex
,
};
static
const
size_t
cSimpleMissionItemSignals
=
maxSignalIndex
;
...
...
@@ -182,7 +197,6 @@ void SimpleMissionItemTest::_testSignals(void)
rgSimpleMissionItemSignals
[
friendlyEditAllowedChangedIndex
]
=
SIGNAL
(
friendlyEditAllowedChanged
(
bool
));
rgSimpleMissionItemSignals
[
headingDegreesChangedIndex
]
=
SIGNAL
(
headingDegreesChanged
(
double
));
rgSimpleMissionItemSignals
[
rawEditChangedIndex
]
=
SIGNAL
(
rawEditChanged
(
bool
));
rgSimpleMissionItemSignals
[
uiModelChangedIndex
]
=
SIGNAL
(
uiModelChanged
());
MissionItem
missionItem
(
1
,
// sequence number
MAV_CMD_NAV_WAYPOINT
,
...
...
@@ -196,7 +210,7 @@ void SimpleMissionItemTest::_testSignals(void)
70.1234567
,
true
,
// autoContinue
false
);
// isCurrentItem
SimpleMissionItem
simpleMissionItem
(
NULL
/* Vehicle */
,
missionItem
);
SimpleMissionItem
simpleMissionItem
(
_offlineVehicle
,
missionItem
);
// It's important top check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
...
...
@@ -209,13 +223,12 @@ void SimpleMissionItemTest::_testSignals(void)
// Check commandChanged signalling. Call setCommand should trigger:
// commandChanged
// dirtyChanged
// uiModelChanged
// coordinateChanged - since altitude will be set back to default
simpleMissionItem
.
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_WAYPOINT
);
QVERIFY
(
multiSpy
->
checkNoSignals
());
simpleMissionItem
.
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_LOITER_TIME
);
QVERIFY
(
multiSpy
->
checkSignalsByMask
(
commandChangedMask
|
dirtyChangedMask
|
uiModelChangedMask
|
coordinateChangedMask
));
QVERIFY
(
multiSpy
->
checkSignalsByMask
(
commandChangedMask
|
dirtyChangedMask
|
coordinateChangedMask
));
multiSpy
->
clearAllSignals
();
// Check coordinateChanged signalling. Calling setCoordinate should trigger:
...
...
src/MissionManager/SimpleMissionItemTest.h
View file @
1b9e036e
...
...
@@ -24,7 +24,10 @@ class SimpleMissionItemTest : public UnitTest
public:
SimpleMissionItemTest
(
void
);
void
init
(
void
)
override
;
void
cleanup
(
void
)
override
;
private
slots
:
void
_testSignals
(
void
);
void
_testEditorFacts
(
void
);
...
...
@@ -48,6 +51,8 @@ private:
bool
relativeAltCheckbox
;
}
ItemExpected_t
;
Vehicle
*
_offlineVehicle
;
static
const
ItemInfo_t
_rgItemInfo
[];
static
const
ItemExpected_t
_rgItemExpected
[];
static
const
FactValue_t
_rgFactValuesWaypoint
[];
...
...
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