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
46582548
Commit
46582548
authored
9 years ago
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Mission Unit Test
parent
6b5e89ca
Changes
10
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
362 additions
and
43 deletions
+362
-43
QGCApplication.pro
QGCApplication.pro
+14
-12
MissionEditor.cc
src/MissionEditor/MissionEditor.cc
+2
-1
MissionItem.cc
src/MissionItem.cc
+8
-7
MissionItem.h
src/MissionItem.h
+2
-2
MissionItemTest.cc
src/MissionItemTest.cc
+182
-0
MissionItemTest.h
src/MissionItemTest.h
+83
-0
MissionManager.cc
src/MissionManager/MissionManager.cc
+2
-2
QGCApplication.cc
src/QGCApplication.cc
+3
-1
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+6
-6
WaypointList.cc
src/ui/WaypointList.cc
+60
-12
No files found.
QGCApplication.pro
View file @
46582548
...
...
@@ -511,40 +511,42 @@ INCLUDEPATH += \
src
/
qgcunittest
HEADERS
+=
\
src
/
qgcunittest
/
FlightGearTest
.
h
\
src
/
qgcunittest
/
MultiSignalSpy
.
h
\
src
/
qgcunittest
/
TCPLinkTest
.
h
\
src
/
qgcunittest
/
TCPLoopBackServer
.
h
\
src
/
FactSystem
/
FactSystemTestBase
.
h
\
src
/
FactSystem
/
FactSystemTestGeneric
.
h
\
src
/
FactSystem
/
FactSystemTestPX4
.
h
\
src
/
MissionItemTest
.
h
\
src
/
qgcunittest
/
FileDialogTest
.
h
\
src
/
qgcunittest
/
FileManagerTest
.
h
\
src
/
qgcunittest
/
FlightGearTest
.
h
\
src
/
qgcunittest
/
LinkManagerTest
.
h
\
src
/
qgcunittest
/
MainWindowTest
.
h
\
src
/
qgcunittest
/
MavlinkLogTest
.
h
\
src
/
qgcunittest
/
MessageBoxTest
.
h
\
src
/
qgcunittest
/
MultiSignalSpy
.
h
\
src
/
qgcunittest
/
PX4RCCalibrationTest
.
h
\
src
/
qgcunittest
/
TCPLinkTest
.
h
\
src
/
qgcunittest
/
TCPLoopBackServer
.
h
\
src
/
qgcunittest
/
UnitTest
.
h
\
src
/
VehicleSetup
/
SetupViewTest
.
h
\
src
/
qgcunittest
/
FileManagerTest
.
h
\
src
/
qgcunittest
/
PX4RCCalibrationTest
.
h
\
SOURCES
+=
\
src
/
qgcunittest
/
FlightGearTest
.
cc
\
src
/
qgcunittest
/
MultiSignalSpy
.
cc
\
src
/
qgcunittest
/
TCPLinkTest
.
cc
\
src
/
qgcunittest
/
TCPLoopBackServer
.
cc
\
src
/
FactSystem
/
FactSystemTestBase
.
cc
\
src
/
FactSystem
/
FactSystemTestGeneric
.
cc
\
src
/
FactSystem
/
FactSystemTestPX4
.
cc
\
src
/
MissionItemTest
.
cc
\
src
/
qgcunittest
/
FileDialogTest
.
cc
\
src
/
qgcunittest
/
FileManagerTest
.
cc
\
src
/
qgcunittest
/
FlightGearTest
.
cc
\
src
/
qgcunittest
/
LinkManagerTest
.
cc
\
src
/
qgcunittest
/
MainWindowTest
.
cc
\
src
/
qgcunittest
/
MavlinkLogTest
.
cc
\
src
/
qgcunittest
/
MessageBoxTest
.
cc
\
src
/
qgcunittest
/
MultiSignalSpy
.
cc
\
src
/
qgcunittest
/
PX4RCCalibrationTest
.
cc
\
src
/
qgcunittest
/
TCPLinkTest
.
cc
\
src
/
qgcunittest
/
TCPLoopBackServer
.
cc
\
src
/
qgcunittest
/
UnitTest
.
cc
\
src
/
VehicleSetup
/
SetupViewTest
.
cc
\
src
/
qgcunittest
/
FileManagerTest
.
cc
\
src
/
qgcunittest
/
PX4RCCalibrationTest
.
cc
\
}
#
DebugBuild
|
WindowsDebugAndRelease
}
#
MobileBuild
...
...
This diff is collapsed.
Click to expand it.
src/MissionEditor/MissionEditor.cc
View file @
46582548
...
...
@@ -104,7 +104,8 @@ int MissionEditor::addMissionItem(QGeoCoordinate coordinate)
qWarning
()
<<
"addMissionItem called with _canEdit == false"
;
}
MissionItem
*
newItem
=
new
MissionItem
(
this
,
_missionItems
->
count
(),
coordinate
);
MissionItem
*
newItem
=
new
MissionItem
(
this
,
_missionItems
->
count
(),
coordinate
,
MAV_CMD_NAV_WAYPOINT
);
newItem
->
setAltitude
(
30
);
if
(
_missionItems
->
count
()
==
0
)
{
newItem
->
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
);
}
...
...
This diff is collapsed.
Click to expand it.
src/MissionItem.cc
View file @
46582548
...
...
@@ -67,16 +67,17 @@ const MissionItem::MavCmd2Name_t MissionItem::_rgMavCmd2Name[_cMavCmd2Name] = {
MissionItem
::
MissionItem
(
QObject
*
parent
,
int
sequenceNumber
,
QGeoCoordinate
coordinate
,
int
command
,
double
param1
,
double
param2
,
double
param3
,
double
param4
,
bool
autocontinue
,
bool
isCurrentItem
,
int
frame
,
int
command
)
int
frame
)
:
QObject
(
parent
)
,
_sequenceNumber
(
sequenceNumber
)
,
_frame
(
-
1
)
// Forces set of _altitudeRelativeToHomeFact
,
_command
((
MavlinkQmlSingleton
::
Qml_MAV_CMD
)
command
)
,
_autocontinue
(
autocontinue
)
,
_isCurrentItem
(
isCurrentItem
)
...
...
@@ -219,7 +220,7 @@ void MissionItem::save(QTextStream &saveStream)
position
=
position
.
arg
(
y
(),
0
,
'g'
,
18
);
position
=
position
.
arg
(
z
(),
0
,
'g'
,
18
);
QString
parameters
(
"%1
\t
%2
\t
%3
\t
%4"
);
parameters
=
parameters
.
arg
(
param
2
(),
0
,
'g'
,
18
).
arg
(
param2
(),
0
,
'g'
,
18
).
arg
(
loiterOrbitRadius
(),
0
,
'g'
,
18
).
arg
(
yawRadians
(),
0
,
'g'
,
18
);
parameters
=
parameters
.
arg
(
param
1
(),
0
,
'g'
,
18
).
arg
(
param2
(),
0
,
'g'
,
18
).
arg
(
loiterOrbitRadius
(),
0
,
'g'
,
18
).
arg
(
yawRadians
(),
0
,
'g'
,
18
);
// FORMAT: <INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <AUTOCONTINUE> <DESCRIPTION>
// as documented here: http://qgroundcontrol.org/waypoint_protocol
saveStream
<<
this
->
sequenceNumber
()
<<
"
\t
"
<<
this
->
isCurrentItem
()
<<
"
\t
"
<<
this
->
frame
()
<<
"
\t
"
<<
this
->
command
()
<<
"
\t
"
<<
parameters
<<
"
\t
"
<<
position
<<
"
\t
"
<<
this
->
autoContinue
()
<<
"
\r\n
"
;
//"\t" << this->getDescription() << "\r\n";
...
...
@@ -280,7 +281,7 @@ void MissionItem::setZ(double z)
void
MissionItem
::
setLatitude
(
double
lat
)
{
if
(
_latitudeFact
->
value
().
toDouble
()
!=
lat
&&
((
_frame
==
MAV_FRAME_GLOBAL
)
||
(
_frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
))
)
if
(
_latitudeFact
->
value
().
toDouble
()
!=
lat
)
{
_latitudeFact
->
setValue
(
lat
);
emit
changed
(
this
);
...
...
@@ -290,7 +291,7 @@ void MissionItem::setLatitude(double lat)
void
MissionItem
::
setLongitude
(
double
lon
)
{
if
(
_longitudeFact
->
value
().
toDouble
()
!=
lon
&&
((
_frame
==
MAV_FRAME_GLOBAL
)
||
(
_frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
))
)
if
(
_longitudeFact
->
value
().
toDouble
()
!=
lon
)
{
_longitudeFact
->
setValue
(
lon
);
emit
changed
(
this
);
...
...
@@ -300,7 +301,7 @@ void MissionItem::setLongitude(double lon)
void
MissionItem
::
setAltitude
(
double
altitude
)
{
if
(
_altitudeFact
->
value
().
toDouble
()
!=
altitude
&&
((
_frame
==
MAV_FRAME_GLOBAL
)
||
(
_frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
))
)
if
(
_altitudeFact
->
value
().
toDouble
()
!=
altitude
)
{
_altitudeFact
->
setValue
(
altitude
);
emit
changed
(
this
);
...
...
@@ -349,7 +350,7 @@ int MissionItem::frame(void) const
void
MissionItem
::
setFrame
(
int
/*MAV_FRAME*/
frame
)
{
if
(
_frame
!=
frame
)
{
_altitudeRelativeToHomeFact
->
setValue
(
_
frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
_altitudeRelativeToHomeFact
->
setValue
(
frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
_frame
=
frame
;
emit
changed
(
this
);
}
...
...
This diff is collapsed.
Click to expand it.
src/MissionItem.h
View file @
46582548
...
...
@@ -47,14 +47,14 @@ public:
MissionItem
(
QObject
*
parent
=
0
,
int
sequenceNumber
=
0
,
QGeoCoordinate
coordiante
=
QGeoCoordinate
(),
int
action
=
MAV_CMD_NAV_WAYPOINT
,
double
param1
=
0
.
0
,
double
param2
=
0
.
0
,
double
param3
=
0
.
0
,
double
param4
=
0
.
0
,
bool
autocontinue
=
true
,
bool
isCurrentItem
=
false
,
int
frame
=
MAV_FRAME_GLOBAL
,
int
action
=
MAV_CMD_NAV_WAYPOINT
);
int
frame
=
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
MissionItem
(
const
MissionItem
&
other
,
QObject
*
parent
=
NULL
);
~
MissionItem
();
...
...
This diff is collapsed.
Click to expand it.
src/MissionItemTest.cc
0 → 100644
View file @
46582548
/*=====================================================================
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 "MissionItemTest.h"
UT_REGISTER_TEST
(
MissionItemTest
)
const
MissionItemTest
::
ItemInfo_t
MissionItemTest
::
_rgItemInfo
[]
=
{
{
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
},
{
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
,
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
,
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
,
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
,
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
,
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
,
QGeoCoordinate
(
-
10.0
,
-
20.0
,
-
30.0
),
MAV_CMD_DO_JUMP
,
10.0
,
20.0
,
30.0
,
40.0
,
true
,
false
,
MAV_FRAME_MISSION
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesWaypoint
[]
=
{
{
"Latitude:"
,
-
10.0
},
{
"Longitude:"
,
-
20.0
},
{
"Altitude:"
,
-
30.0
},
{
"Heading:"
,
40.0
},
{
"Radius:"
,
20.0
},
{
"Hold:"
,
10.0
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesLoiterUnlim
[]
=
{
{
"Latitude:"
,
-
10.0
},
{
"Longitude:"
,
-
20.0
},
{
"Altitude:"
,
-
30.0
},
{
"Heading:"
,
40.0
},
{
"Radius:"
,
30.0
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesLoiterTurns
[]
=
{
{
"Latitude:"
,
-
10.0
},
{
"Longitude:"
,
-
20.0
},
{
"Altitude:"
,
-
30.0
},
{
"Heading:"
,
40.0
},
{
"Radius:"
,
30.0
},
{
"Turns:"
,
10.0
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesLoiterTime
[]
=
{
{
"Latitude:"
,
-
10.0
},
{
"Longitude:"
,
-
20.0
},
{
"Altitude:"
,
-
30.0
},
{
"Heading:"
,
40.0
},
{
"Radius:"
,
30.0
},
{
"Seconds:"
,
10.0
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesLand
[]
=
{
{
"Latitude:"
,
-
10.0
},
{
"Longitude:"
,
-
20.0
},
{
"Altitude:"
,
-
30.0
},
{
"Heading:"
,
40.0
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesTakeoff
[]
=
{
{
"Latitude:"
,
-
10.0
},
{
"Longitude:"
,
-
20.0
},
{
"Altitude:"
,
-
30.0
},
{
"Heading:"
,
40.0
},
{
"Pitch:"
,
10.0
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesConditionDelay
[]
=
{
{
"Seconds:"
,
10.0
},
};
const
MissionItemTest
::
FactValue_t
MissionItemTest
::
_rgFactValuesDoJump
[]
=
{
{
"Seq #:"
,
10.0
},
{
"Repeat:"
,
20.0
},
};
const
MissionItemTest
::
ItemExpected_t
MissionItemTest
::
_rgItemExpected
[]
=
{
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesWaypoint
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesWaypoint
[
0
]),
MissionItemTest
::
_rgFactValuesWaypoint
},
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesLoiterUnlim
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesLoiterUnlim
[
0
]),
MissionItemTest
::
_rgFactValuesLoiterUnlim
},
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesLoiterTurns
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesLoiterTurns
[
0
]),
MissionItemTest
::
_rgFactValuesLoiterTurns
},
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesLoiterTime
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesLoiterTime
[
0
]),
MissionItemTest
::
_rgFactValuesLoiterTime
},
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesLand
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesLand
[
0
]),
MissionItemTest
::
_rgFactValuesLand
},
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesTakeoff
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesTakeoff
[
0
]),
MissionItemTest
::
_rgFactValuesTakeoff
},
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesConditionDelay
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesConditionDelay
[
0
]),
MissionItemTest
::
_rgFactValuesConditionDelay
},
{
"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
"
,
sizeof
(
MissionItemTest
::
_rgFactValuesDoJump
)
/
sizeof
(
MissionItemTest
::
_rgFactValuesDoJump
[
0
]),
MissionItemTest
::
_rgFactValuesDoJump
},
};
MissionItemTest
::
MissionItemTest
(
void
)
{
}
void
MissionItemTest
::
_test
(
void
)
{
for
(
size_t
i
=
0
;
i
<
sizeof
(
_rgItemInfo
)
/
sizeof
(
_rgItemInfo
[
0
]);
i
++
)
{
const
ItemInfo_t
*
info
=
&
_rgItemInfo
[
i
];
const
ItemExpected_t
*
expected
=
&
_rgItemExpected
[
i
];
qDebug
()
<<
"Command:"
<<
info
->
command
;
MissionItem
*
item
=
new
MissionItem
(
NULL
,
info
->
sequenceNumber
,
info
->
coordinate
,
info
->
command
,
info
->
param1
,
info
->
param2
,
info
->
param3
,
info
->
param4
,
info
->
autocontinue
,
info
->
isCurrentItem
,
info
->
frame
);
// Validate the saving is working correctly
QString
savedItemString
;
QTextStream
saveStream
(
&
savedItemString
,
QIODevice
::
WriteOnly
);
item
->
save
(
saveStream
);
QCOMPARE
(
savedItemString
,
QString
(
expected
->
streamString
));
// Validate that the fact values are correctly returned
size_t
factCount
=
0
;
for
(
int
i
=
0
;
i
<
item
->
textFieldFacts
()
->
count
();
i
++
)
{
Fact
*
fact
=
qobject_cast
<
Fact
*>
(
item
->
textFieldFacts
()
->
get
(
i
));
bool
found
=
false
;
for
(
size_t
j
=
0
;
j
<
expected
->
cFactValues
;
j
++
)
{
const
FactValue_t
*
factValue
=
&
expected
->
rgFactValues
[
j
];
if
(
factValue
->
name
==
fact
->
name
())
{
qDebug
()
<<
factValue
->
name
;
QCOMPARE
(
fact
->
value
().
toDouble
(),
factValue
->
value
);
factCount
++
;
found
=
true
;
break
;
}
}
QVERIFY
(
found
);
}
QCOMPARE
(
factCount
,
expected
->
cFactValues
);
// Validate that loading is working correctly
MissionItem
*
loadedItem
=
new
MissionItem
();
QTextStream
loadStream
(
&
savedItemString
,
QIODevice
::
ReadOnly
);
QVERIFY
(
loadedItem
->
load
(
loadStream
));
//qDebug() << savedItemString;
QCOMPARE
(
loadedItem
->
coordinate
().
latitude
(),
item
->
coordinate
().
latitude
());
QCOMPARE
(
loadedItem
->
coordinate
().
longitude
(),
item
->
coordinate
().
longitude
());
QCOMPARE
(
loadedItem
->
coordinate
().
altitude
(),
item
->
coordinate
().
altitude
());
QCOMPARE
(
loadedItem
->
command
(),
item
->
command
());
QCOMPARE
(
loadedItem
->
param1
(),
item
->
param1
());
QCOMPARE
(
loadedItem
->
param2
(),
item
->
param2
());
QCOMPARE
(
loadedItem
->
param3
(),
item
->
param3
());
QCOMPARE
(
loadedItem
->
param4
(),
item
->
param4
());
QCOMPARE
(
loadedItem
->
autoContinue
(),
item
->
autoContinue
());
QCOMPARE
(
loadedItem
->
isCurrentItem
(),
item
->
isCurrentItem
());
QCOMPARE
(
loadedItem
->
frame
(),
item
->
frame
());
delete
item
;
delete
loadedItem
;
}
}
This diff is collapsed.
Click to expand it.
src/MissionItemTest.h
0 → 100644
View file @
46582548
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 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/>.
======================================================================*/
#ifndef MissionItemTest_H
#define MissionItemTest_H
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
/// @file
/// @brief FlightGear HIL Simulation unit tests
///
/// @author Don Gagne <don@thegagnes.com>
class
MissionItemTest
:
public
UnitTest
{
Q_OBJECT
public:
MissionItemTest
(
void
);
private
slots
:
void
_test
(
void
);
private:
typedef
struct
{
int
sequenceNumber
;
QGeoCoordinate
coordinate
;
int
command
;
double
param1
;
double
param2
;
double
param3
;
double
param4
;
bool
autocontinue
;
bool
isCurrentItem
;
int
frame
;
}
ItemInfo_t
;
typedef
struct
{
const
char
*
name
;
double
value
;
}
FactValue_t
;
typedef
struct
{
const
char
*
streamString
;
size_t
cFactValues
;
const
FactValue_t
*
rgFactValues
;
}
ItemExpected_t
;
static
const
ItemInfo_t
_rgItemInfo
[];
static
const
ItemExpected_t
_rgItemExpected
[];
static
const
FactValue_t
_rgFactValuesWaypoint
[];
static
const
FactValue_t
_rgFactValuesLoiterUnlim
[];
static
const
FactValue_t
_rgFactValuesLoiterTurns
[];
static
const
FactValue_t
_rgFactValuesLoiterTime
[];
static
const
FactValue_t
_rgFactValuesLand
[];
static
const
FactValue_t
_rgFactValuesTakeoff
[];
static
const
FactValue_t
_rgFactValuesConditionDelay
[];
static
const
FactValue_t
_rgFactValuesDoJump
[];
};
#endif
This diff is collapsed.
Click to expand it.
src/MissionManager/MissionManager.cc
View file @
46582548
...
...
@@ -222,14 +222,14 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
MissionItem
*
item
=
new
MissionItem
(
this
,
missionItem
.
seq
,
QGeoCoordinate
(
missionItem
.
x
,
missionItem
.
y
,
missionItem
.
z
),
missionItem
.
command
,
missionItem
.
param1
,
missionItem
.
param2
,
missionItem
.
param3
,
missionItem
.
param3
,
missionItem
.
autocontinue
,
missionItem
.
current
,
missionItem
.
frame
,
missionItem
.
command
);
missionItem
.
frame
);
_missionItems
.
append
(
item
);
if
(
!
item
->
canEdit
())
{
...
...
This diff is collapsed.
Click to expand it.
src/QGCApplication.cc
View file @
46582548
...
...
@@ -162,7 +162,9 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
,
_runningUnitTests
(
unitTesting
)
,
_styleIsDark
(
true
)
,
_fakeMobile
(
false
)
,
_useNewMissionEditor
(
false
)
#ifdef UNITTEST_BUILD
,
_useNewMissionEditor
(
true
)
// Unit Tests run new mission editor
#endif
#ifdef QT_DEBUG
,
_testHighDPI
(
false
)
#endif
...
...
This diff is collapsed.
Click to expand it.
src/uas/UASWaypointManager.cc
View file @
46582548
...
...
@@ -199,14 +199,14 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
MissionItem
*
lwp_vo
=
new
MissionItem
(
NULL
,
wp
->
seq
,
QGeoCoordinate
(
wp
->
x
,
wp
->
y
,
wp
->
z
),
(
MAV_CMD
)
wp
->
command
,
wp
->
param1
,
wp
->
param2
,
wp
->
param3
,
wp
->
param4
,
wp
->
autocontinue
,
wp
->
current
,
(
MAV_FRAME
)
wp
->
frame
,
(
MAV_CMD
)
wp
->
command
);
(
MAV_FRAME
)
wp
->
frame
);
addWaypointViewOnly
(
lwp_vo
);
...
...
@@ -214,14 +214,14 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
MissionItem
*
lwp_ed
=
new
MissionItem
(
NULL
,
wp
->
seq
,
QGeoCoordinate
(
wp
->
x
,
wp
->
y
,
wp
->
z
),
(
MAV_CMD
)
wp
->
command
,
wp
->
param1
,
wp
->
param2
,
wp
->
param3
,
wp
->
param4
,
wp
->
autocontinue
,
wp
->
current
,
(
MAV_FRAME
)
wp
->
frame
,
(
MAV_CMD
)
wp
->
command
);
(
MAV_FRAME
)
wp
->
frame
);
addWaypointEditable
(
lwp_ed
,
false
);
if
(
wp
->
current
==
1
)
currentWaypointEditable
=
lwp_ed
;
}
...
...
@@ -256,14 +256,14 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
MissionItem
*
lwp_vo
=
new
MissionItem
(
NULL
,
wp
->
seq
,
QGeoCoordinate
(
wp
->
x
,
wp
->
y
,
wp
->
z
),
(
MAV_CMD
)
wp
->
command
,
wp
->
param1
,
wp
->
param2
,
wp
->
param3
,
wp
->
param4
,
wp
->
autocontinue
,
wp
->
current
,
(
MAV_FRAME
)
wp
->
frame
,
(
MAV_CMD
)
wp
->
command
);
(
MAV_FRAME
)
wp
->
frame
);
waypointsViewOnly
.
replace
(
wp
->
seq
,
lwp_vo
);
emit
waypointViewOnlyListChanged
();
...
...
This diff is collapsed.
Click to expand it.
src/ui/WaypointList.cc
View file @
46582548
...
...
@@ -304,9 +304,17 @@ void WaypointList::addEditable(bool onCurrentPosition)
}
else
{
updateStatusLabel
(
tr
(
"Added default GLOBAL (Relative alt.) waypoint."
));
}
wp
=
new
MissionItem
(
NULL
,
0
,
wp
=
new
MissionItem
(
NULL
,
0
,
QGeoCoordinate
(
uas
->
getLatitude
(),
uas
->
getLongitude
(),
uas
->
getAltitudeAMSL
()),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
(),
MAV_CMD_NAV_WAYPOINT
);
MAV_CMD_NAV_WAYPOINT
,
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
());
WPM
->
addWaypointEditable
(
wp
);
}
else
{
...
...
@@ -316,9 +324,17 @@ void WaypointList::addEditable(bool onCurrentPosition)
}
else
{
updateStatusLabel
(
tr
(
"Added default GLOBAL (Relative alt.) waypoint."
));
}
wp
=
new
MissionItem
(
NULL
,
0
,
wp
=
new
MissionItem
(
NULL
,
0
,
QGeoCoordinate
(
HomePositionManager
::
instance
()
->
getHomeLatitude
(),
HomePositionManager
::
instance
()
->
getHomeLongitude
(),
WPM
->
getAltitudeRecommendation
()),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
(),
MAV_CMD_NAV_WAYPOINT
);
MAV_CMD_NAV_WAYPOINT
,
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
());
WPM
->
addWaypointEditable
(
wp
);
}
}
...
...
@@ -327,15 +343,31 @@ void WaypointList::addEditable(bool onCurrentPosition)
if
(
onCurrentPosition
)
{
updateStatusLabel
(
tr
(
"Added default LOCAL (NED) waypoint."
));
wp
=
new
MissionItem
(
NULL
,
0
,
wp
=
new
MissionItem
(
NULL
,
0
,
QGeoCoordinate
(
uas
->
getLocalX
(),
uas
->
getLocalY
(),
uas
->
getLocalZ
()),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
MAV_FRAME_LOCAL_NED
,
MAV_CMD_NAV_WAYPOINT
);
MAV_CMD_NAV_WAYPOINT
,
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
MAV_FRAME_LOCAL_NED
);
WPM
->
addWaypointEditable
(
wp
);
}
else
{
updateStatusLabel
(
tr
(
"Added default LOCAL (NED) waypoint."
));
wp
=
new
MissionItem
(
0
,
0
,
wp
=
new
MissionItem
(
0
,
0
,
QGeoCoordinate
(
0
,
0
,
-
0.50
),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
MAV_FRAME_LOCAL_NED
,
MAV_CMD_NAV_WAYPOINT
);
MAV_CMD_NAV_WAYPOINT
,
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
MAV_FRAME_LOCAL_NED
);
WPM
->
addWaypointEditable
(
wp
);
}
}
...
...
@@ -343,9 +375,17 @@ void WaypointList::addEditable(bool onCurrentPosition)
{
// MAV connected, but position unknown, add default waypoint
updateStatusLabel
(
tr
(
"WARNING: No position known. Adding default LOCAL (NED) waypoint"
));
wp
=
new
MissionItem
(
NULL
,
0
,
wp
=
new
MissionItem
(
NULL
,
0
,
QGeoCoordinate
(
HomePositionManager
::
instance
()
->
getHomeLatitude
(),
HomePositionManager
::
instance
()
->
getHomeLongitude
(),
WPM
->
getAltitudeRecommendation
()),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
(),
MAV_CMD_NAV_WAYPOINT
);
MAV_CMD_NAV_WAYPOINT
,
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
());
WPM
->
addWaypointEditable
(
wp
);
}
}
...
...
@@ -353,9 +393,17 @@ void WaypointList::addEditable(bool onCurrentPosition)
{
//Since no UAV available, create first default waypoint.
updateStatusLabel
(
tr
(
"No UAV connected. Adding default GLOBAL (NED) waypoint"
));
wp
=
new
MissionItem
(
NULL
,
0
,
wp
=
new
MissionItem
(
NULL
,
0
,
QGeoCoordinate
(
HomePositionManager
::
instance
()
->
getHomeLatitude
(),
HomePositionManager
::
instance
()
->
getHomeLongitude
(),
WPM
->
getAltitudeRecommendation
()),
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
(),
MAV_CMD_NAV_WAYPOINT
);
MAV_CMD_NAV_WAYPOINT
,
0
,
WPM
->
getAcceptanceRadiusRecommendation
(),
0
,
0
,
true
,
true
,
(
MAV_FRAME
)
WPM
->
getFrameRecommendation
());
WPM
->
addWaypointEditable
(
wp
);
}
}
...
...
This diff is collapsed.
Click to expand it.
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