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
c71266c2
Commit
c71266c2
authored
Oct 20, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Match 1-based editor/manager usage pattern
parent
84867663
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
27 additions
and
9 deletions
+27
-9
MissionManagerTest.cc
src/MissionManager/MissionManagerTest.cc
+27
-9
No files found.
src/MissionManager/MissionManagerTest.cc
View file @
c71266c2
...
...
@@ -28,14 +28,14 @@
UT_REGISTER_TEST
(
MissionManagerTest
)
const
MissionManagerTest
::
TestCase_t
MissionManagerTest
::
_rgTestCases
[]
=
{
{
"
1
\t
0
\t
3
\t
16
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_WAYPOINT
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
0
\t
0
\t
3
\t
16
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
0
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_WAYPOINT
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"1
\t
0
\t
3
\t
17
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_LOITER_UNLIM
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
1
\t
0
\t
3
\t
18
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_LOITER_TURNS
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
1
\t
0
\t
3
\t
19
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_LOITER_TIME
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
1
\t
0
\t
3
\t
21
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_LAND
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
1
\t
0
\t
3
\t
22
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_TAKEOFF
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
1
\t
0
\t
2
\t
112
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_CONDITION_DELAY
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_MISSION
}
},
{
"
1
\t
0
\t
2
\t
177
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
1
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_DO_JUMP
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_MISSION
}
},
{
"
2
\t
0
\t
3
\t
18
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
2
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_LOITER_TURNS
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
3
\t
0
\t
3
\t
19
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
3
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_LOITER_TIME
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
4
\t
0
\t
3
\t
21
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
4
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_LAND
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
5
\t
0
\t
3
\t
22
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
5
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_NAV_TAKEOFF
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
}
},
{
"
6
\t
0
\t
2
\t
112
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
6
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_CONDITION_DELAY
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_MISSION
}
},
{
"
7
\t
0
\t
2
\t
177
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
,
{
7
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_DO_JUMP
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_MISSION
}
},
};
MissionManagerTest
::
MissionManagerTest
(
void
)
...
...
@@ -146,6 +146,16 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
const
size_t
cTestCases
=
sizeof
(
_rgTestCases
)
/
sizeof
(
_rgTestCases
[
0
]);
QmlObjectListModel
*
list
=
new
QmlObjectListModel
();
// Editor has a home position item on the front, so we do the same
MissionItem
*
homeItem
=
new
MissionItem
(
this
);
homeItem
->
setHomePositionSpecialCase
(
true
);
homeItem
->
setHomePositionValid
(
false
);
homeItem
->
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_WAYPOINT
);
homeItem
->
setLatitude
(
47.3769
);
homeItem
->
setLongitude
(
8.549444
);
homeItem
->
setSequenceNumber
(
0
);
list
->
insert
(
0
,
homeItem
);
for
(
size_t
i
=
0
;
i
<
cTestCases
;
i
++
)
{
const
TestCase_t
*
testCase
=
&
_rgTestCases
[
i
];
...
...
@@ -153,12 +163,19 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
QTextStream
loadStream
(
testCase
->
itemStream
,
QIODevice
::
ReadOnly
);
QVERIFY
(
item
->
load
(
loadStream
));
// Mission Manager expects to get 1-base sequence numbers for write
item
->
setSequenceNumber
(
item
->
sequenceNumber
()
+
1
);
if
(
item
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_DO_JUMP
)
{
item
->
setParam1
((
int
)
item
->
param1
()
+
1
);
}
list
->
append
(
item
);
}
// Send the items to the vehicle
_missionManager
->
writeMissionItems
(
*
list
,
fals
e
/* skipFirstItem */
);
_missionManager
->
writeMissionItems
(
*
list
,
tru
e
/* skipFirstItem */
);
// writeMissionItems should emit these signals before returning:
// inProgressChanged
...
...
@@ -304,16 +321,17 @@ void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode
MissionItem
*
actual
=
qobject_cast
<
MissionItem
*>
(
_missionManager
->
missionItems
()
->
get
(
i
));
qDebug
()
<<
"Test case"
<<
i
;
QCOMPARE
(
actual
->
sequenceNumber
(),
testCase
->
expectedItem
.
sequenceNumber
);
QCOMPARE
(
actual
->
coordinate
().
latitude
(),
testCase
->
expectedItem
.
coordinate
.
latitude
());
QCOMPARE
(
actual
->
coordinate
().
longitude
(),
testCase
->
expectedItem
.
coordinate
.
longitude
());
QCOMPARE
(
actual
->
coordinate
().
altitude
(),
testCase
->
expectedItem
.
coordinate
.
altitude
());
QCOMPARE
((
int
)
actual
->
command
(),
(
int
)
testCase
->
expectedItem
.
command
);
QCOMPARE
(
actual
->
param1
(),
testCase
->
expectedItem
.
param1
);
QCOMPARE
(
actual
->
param2
(),
testCase
->
expectedItem
.
param2
);
QCOMPARE
(
actual
->
param3
(),
testCase
->
expectedItem
.
param3
);
QCOMPARE
(
actual
->
param4
(),
testCase
->
expectedItem
.
param4
);
QCOMPARE
(
actual
->
autoContinue
(),
testCase
->
expectedItem
.
autocontinue
);
QCOMPARE
(
actual
->
frame
(),
testCase
->
expectedItem
.
frame
);
QCOMPARE
(
actual
->
param1
(),
testCase
->
expectedItem
.
param1
);
}
}
...
...
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