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
92e7bf38
Commit
92e7bf38
authored
Nov 01, 2018
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
4d0fd52a
Changes
17
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
17 changed files
with
667 additions
and
132 deletions
+667
-132
ChangeLog.md
ChangeLog.md
+1
-0
qgroundcontrol.pro
qgroundcontrol.pro
+2
-0
CameraSection.cc
src/MissionManager/CameraSection.cc
+94
-51
CameraSection.h
src/MissionManager/CameraSection.h
+7
-2
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+31
-21
CameraSectionTest.h
src/MissionManager/CameraSectionTest.h
+5
-1
FWLandingPattern.FactMetaData.json
src/MissionManager/FWLandingPattern.FactMetaData.json
+12
-0
FWLandingPatternTest.cc
src/MissionManager/FWLandingPatternTest.cc
+238
-0
FWLandingPatternTest.h
src/MissionManager/FWLandingPatternTest.h
+54
-0
FixedWingLandingComplexItem.cc
src/MissionManager/FixedWingLandingComplexItem.cc
+147
-41
FixedWingLandingComplexItem.h
src/MissionManager/FixedWingLandingComplexItem.h
+19
-0
SectionTest.cc
src/MissionManager/SectionTest.cc
+0
-15
SectionTest.h
src/MissionManager/SectionTest.h
+0
-1
FWLandingPatternEditor.qml
src/PlanView/FWLandingPatternEditor.qml
+29
-0
UnitTest.cc
src/qgcunittest/UnitTest.cc
+20
-0
UnitTest.h
src/qgcunittest/UnitTest.h
+6
-0
UnitTestList.cc
src/qgcunittest/UnitTestList.cc
+2
-0
No files found.
ChangeLog.md
View file @
92e7bf38
...
...
@@ -12,6 +12,7 @@ Note: This file only contains high level features or important fixes.
*
Make Distance to GCS available for display from instrument panel.
*
Make Heading to Home available for display from instrument panel.
*
Edit Position dialog available on polygon vertices.
*
Fixed Wing Landing Pattern: Add stop photo/video support. Defaults to on such that doing an RTL will stop camera.
## 3.4
...
...
qgroundcontrol.pro
View file @
92e7bf38
...
...
@@ -434,6 +434,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src
/
MissionManager
/
CameraCalcTest
.
h
\
src
/
MissionManager
/
CameraSectionTest
.
h
\
src
/
MissionManager
/
CorridorScanComplexItemTest
.
h
\
src
/
MissionManager
/
FWLandingPatternTest
.
h
\
src
/
MissionManager
/
MissionCommandTreeTest
.
h
\
src
/
MissionManager
/
MissionControllerManagerTest
.
h
\
src
/
MissionManager
/
MissionControllerTest
.
h
\
...
...
@@ -475,6 +476,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src
/
MissionManager
/
CameraCalcTest
.
cc
\
src
/
MissionManager
/
CameraSectionTest
.
cc
\
src
/
MissionManager
/
CorridorScanComplexItemTest
.
cc
\
src
/
MissionManager
/
FWLandingPatternTest
.
cc
\
src
/
MissionManager
/
MissionCommandTreeTest
.
cc
\
src
/
MissionManager
/
MissionControllerManagerTest
.
cc
\
src
/
MissionManager
/
MissionControllerTest
.
cc
\
...
...
src/MissionManager/CameraSection.cc
View file @
92e7bf38
This diff is collapsed.
Click to expand it.
src/MissionManager/CameraSection.h
View file @
92e7bf38
...
...
@@ -67,6 +67,13 @@ public:
///< @return The gimbal pitch specified by this item, NaN if not specified
double
specifiedGimbalPitch
(
void
)
const
;
static
bool
scanStopTakingPhotos
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
bool
removeScannedItems
);
static
bool
scanStopTakingVideo
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
bool
removeScannedItems
);
static
void
appendStopTakingPhotos
(
QList
<
MissionItem
*>&
items
,
int
&
seqNum
,
QObject
*
missionItemParent
);
static
void
appendStopTakingVideo
(
QList
<
MissionItem
*>&
items
,
int
&
seqNum
,
QObject
*
missionItemParent
);
static
int
stopTakingPhotosCommandCount
(
void
)
{
return
2
;
}
static
int
stopTakingVideoCommandCount
(
void
)
{
return
1
;
}
// Overrides from Section
bool
available
(
void
)
const
override
{
return
_available
;
}
bool
dirty
(
void
)
const
override
{
return
_dirty
;
}
...
...
@@ -97,11 +104,9 @@ private:
bool
_scanGimbal
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTakePhoto
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTakePhotosIntervalTime
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanStopTakingPhotos
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTriggerStartDistance
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTriggerStopDistance
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTakeVideo
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanStopTakingVideo
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanSetCameraMode
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_available
;
...
...
src/MissionManager/CameraSectionTest.cc
View file @
92e7bf38
...
...
@@ -20,9 +20,6 @@ CameraSectionTest::CameraSectionTest(void)
,
_validDistanceItem
(
NULL
)
,
_validTimeItem
(
NULL
)
,
_validStartVideoItem
(
NULL
)
,
_validStopVideoItem
(
NULL
)
,
_validStopDistanceItem
(
NULL
)
,
_validStopTimeItem
(
NULL
)
,
_validCameraPhotoModeItem
(
NULL
)
,
_validCameraVideoModeItem
(
NULL
)
,
_validCameraSurveyPhotoModeItem
(
NULL
)
...
...
@@ -75,18 +72,6 @@ void CameraSectionTest::init(void)
true
,
// autocontinue
false
),
// isCurrentItem
this
);
_validStopVideoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
false
,
// flyView
MissionItem
(
0
,
MAV_CMD_VIDEO_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
true
,
false
),
this
);
_validStopDistanceItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
false
,
// flyView
MissionItem
(
0
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
true
,
false
),
this
);
_validStopTimeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
false
,
// flyView
MissionItem
(
1
,
MAV_CMD_IMAGE_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
true
,
false
),
this
);
_validCameraPhotoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
false
,
// flyView
MissionItem
(
0
,
// sequence number
...
...
@@ -132,6 +117,10 @@ void CameraSectionTest::init(void)
true
,
// autoContinue
false
),
// isCurrentItem
this
);
_validStopVideoItem
=
createValidStopVideoItem
(
_offlineVehicle
,
this
);
_validStopDistanceItem
=
createValidStopDistanceItem
(
_offlineVehicle
,
this
);
_validStopTimeItem
=
createValidStopTimeItem
(
_offlineVehicle
,
this
);
}
void
CameraSectionTest
::
cleanup
(
void
)
...
...
@@ -471,8 +460,6 @@ void CameraSectionTest::_testAppendSectionItems(void)
QCOMPARE
(
seqNum
,
0
);
rgMissionItems
.
clear
();
// Test specifyGimbal
_cameraSection
->
setSpecifyGimbal
(
true
);
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
_validGimbalItem
->
missionItem
().
param1
());
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
_validGimbalItem
->
missionItem
().
param3
());
...
...
@@ -484,8 +471,6 @@ void CameraSectionTest::_testAppendSectionItems(void)
rgMissionItems
.
clear
();
seqNum
=
0
;
// Test specifyCameraMode
_cameraSection
->
setSpecifyCameraMode
(
true
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
CAMERA_MODE_IMAGE
);
_cameraSection
->
appendSectionItems
(
rgMissionItems
,
this
,
seqNum
);
...
...
@@ -910,7 +895,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
/*
MAV_CMD_VIDEO_STOP_CAPTURE Stop the current video capture (recording)
Mission Param #1 Reserved (Set to 0)
*/
*/
SimpleMissionItem
*
newValidStopVideoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
false
/* flyView */
,
this
);
newValidStopVideoItem
->
missionItem
()
=
_validStopVideoItem
->
missionItem
();
...
...
@@ -941,7 +926,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
visualItems
.
clear
();
}
void
CameraSectionTest
::
_testScanForStop
Image
Section
(
void
)
void
CameraSectionTest
::
_testScanForStop
Photo
Section
(
void
)
{
QCOMPARE
(
_cameraSection
->
available
(),
true
);
...
...
@@ -1124,3 +1109,28 @@ void CameraSectionTest::_testSpecifiedGimbalValuesChanged(void)
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spyCamera
->
checkSignalByMask
(
specifiedGimbalPitchChangedMask
));
}
SimpleMissionItem
*
CameraSectionTest
::
createValidStopVideoItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
{
return
new
SimpleMissionItem
(
vehicle
,
false
,
// flyView
MissionItem
(
0
,
MAV_CMD_VIDEO_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
qQNaN
(),
qQNaN
(),
qQNaN
(),
qQNaN
(),
qQNaN
(),
qQNaN
(),
true
,
false
),
parent
);
}
SimpleMissionItem
*
CameraSectionTest
::
createValidStopDistanceItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
{
return
new
SimpleMissionItem
(
vehicle
,
false
,
// flyView
MissionItem
(
0
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
true
,
false
),
parent
);
}
SimpleMissionItem
*
CameraSectionTest
::
createValidStopTimeItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
{
return
new
SimpleMissionItem
(
vehicle
,
false
,
// flyView
MissionItem
(
1
,
MAV_CMD_IMAGE_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
qQNaN
(),
qQNaN
(),
qQNaN
(),
qQNaN
(),
qQNaN
(),
qQNaN
(),
true
,
false
),
parent
);
}
src/MissionManager/CameraSectionTest.h
View file @
92e7bf38
...
...
@@ -23,6 +23,10 @@ public:
void
init
(
void
)
override
;
void
cleanup
(
void
)
override
;
static
SimpleMissionItem
*
createValidStopVideoItem
(
Vehicle
*
vehicle
,
QObject
*
parent
);
static
SimpleMissionItem
*
createValidStopDistanceItem
(
Vehicle
*
vehicle
,
QObject
*
parent
);
static
SimpleMissionItem
*
createValidStopTimeItem
(
Vehicle
*
vehicle
,
QObject
*
parent
);
private
slots
:
void
_testDirty
(
void
);
void
_testSettingsAvailable
(
void
);
...
...
@@ -34,7 +38,7 @@ private slots:
void
_testScanForPhotoIntervalDistanceSection
(
void
);
void
_testScanForStartVideoSection
(
void
);
void
_testScanForStopVideoSection
(
void
);
void
_testScanForStop
Image
Section
(
void
);
void
_testScanForStop
Photo
Section
(
void
);
void
_testScanForCameraModeSection
(
void
);
void
_testScanForTakePhotoSection
(
void
);
void
_testScanForMultipleItems
(
void
);
...
...
src/MissionManager/FWLandingPattern.FactMetaData.json
View file @
92e7bf38
...
...
@@ -52,5 +52,17 @@
"max"
:
90
,
"decimalPlaces"
:
1
,
"defaultValue"
:
12.0
},
{
"name"
:
"StopTakingPhotos"
,
"shortDescription"
:
"Stop taking photos"
,
"type"
:
"bool"
,
"defaultValue"
:
true
},
{
"name"
:
"StopTakingVideo"
,
"shortDescription"
:
"Stop taking video"
,
"type"
:
"bool"
,
"defaultValue"
:
true
}
]
src/MissionManager/FWLandingPatternTest.cc
0 → 100644
View file @
92e7bf38
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "FWLandingPatternTest.h"
#include "QGCApplication.h"
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
#include "CameraSectionTest.h"
FWLandingPatternTest
::
FWLandingPatternTest
(
void
)
:
_offlineVehicle
(
Q_NULLPTR
)
,
_fwItem
(
Q_NULLPTR
)
,
_multiSpy
(
Q_NULLPTR
)
,
_validStopVideoItem
(
Q_NULLPTR
)
,
_validStopDistanceItem
(
Q_NULLPTR
)
,
_validStopTimeItem
(
Q_NULLPTR
)
{
}
void
FWLandingPatternTest
::
init
(
void
)
{
UnitTest
::
init
();
rgSignals
[
dirtyChangedIndex
]
=
SIGNAL
(
dirtyChanged
(
bool
));
_offlineVehicle
=
new
Vehicle
(
MAV_AUTOPILOT_PX4
,
MAV_TYPE_QUADROTOR
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
(),
this
);
_fwItem
=
new
FixedWingLandingComplexItem
(
_offlineVehicle
,
false
/* flyView */
,
this
);
_multiSpy
=
new
MultiSignalSpy
();
QCOMPARE
(
_multiSpy
->
init
(
_fwItem
,
rgSignals
,
cSignals
),
true
);
// Start in a clean state
QVERIFY
(
!
_fwItem
->
dirty
());
_fwItem
->
setLandingCoordinate
(
QGeoCoordinate
(
47
,
-
122
));
_fwItem
->
setDirty
(
false
);
QVERIFY
(
!
_fwItem
->
dirty
());
_multiSpy
->
clearAllSignals
();
_validStopVideoItem
=
CameraSectionTest
::
createValidStopTimeItem
(
_offlineVehicle
,
this
);
_validStopDistanceItem
=
CameraSectionTest
::
createValidStopTimeItem
(
_offlineVehicle
,
this
);
_validStopTimeItem
=
CameraSectionTest
::
createValidStopTimeItem
(
_offlineVehicle
,
this
);
}
void
FWLandingPatternTest
::
cleanup
(
void
)
{
delete
_fwItem
;
delete
_offlineVehicle
;
delete
_multiSpy
;
delete
_validStopVideoItem
;
delete
_validStopDistanceItem
;
delete
_validStopTimeItem
;
UnitTest
::
cleanup
();
}
void
FWLandingPatternTest
::
_testDefaults
(
void
)
{
QCOMPARE
(
_fwItem
->
stopTakingPhotos
()
->
rawValue
().
toBool
(),
true
);
QCOMPARE
(
_fwItem
->
stopTakingVideo
()
->
rawValue
().
toBool
(),
true
);
}
void
FWLandingPatternTest
::
_testItemCount
(
void
)
{
QList
<
MissionItem
*>
items
;
_fwItem
->
stopTakingPhotos
()
->
setRawValue
(
true
);
_fwItem
->
stopTakingVideo
()
->
setRawValue
(
true
);
_fwItem
->
appendMissionItems
(
items
,
this
);
QCOMPARE
(
items
.
count
(),
3
+
CameraSection
::
stopTakingPhotosCommandCount
()
+
CameraSection
::
stopTakingVideoCommandCount
());
QCOMPARE
(
items
.
count
()
-
1
,
_fwItem
->
lastSequenceNumber
());
items
.
clear
();
_fwItem
->
stopTakingPhotos
()
->
setRawValue
(
false
);
_fwItem
->
stopTakingVideo
()
->
setRawValue
(
false
);
_fwItem
->
appendMissionItems
(
items
,
this
);
QCOMPARE
(
items
.
count
(),
3
);
QCOMPARE
(
items
.
count
()
-
1
,
_fwItem
->
lastSequenceNumber
());
items
.
clear
();
}
void
FWLandingPatternTest
::
_testAppendSectionItems
(
void
)
{
QList
<
MissionItem
*>
rgMissionItems
;
// Create the set of appended mission items
_fwItem
->
stopTakingPhotos
()
->
setRawValue
(
true
);
_fwItem
->
stopTakingVideo
()
->
setRawValue
(
true
);
_fwItem
->
appendMissionItems
(
rgMissionItems
,
this
);
// Convert to visual items
QmlObjectListModel
*
simpleItems
=
new
QmlObjectListModel
(
this
);
for
(
MissionItem
*
item
:
rgMissionItems
)
{
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
false
/* flyView */
,
simpleItems
);
simpleItem
->
missionItem
()
=
*
item
;
simpleItems
->
append
(
simpleItem
);
}
// Scan the items back in to verify the same values come back
// Note that the compares does the best it can with doubles going to floats and back causing inaccuracies beyond a fuzzy compare.
QVERIFY
(
FixedWingLandingComplexItem
::
scanForItem
(
simpleItems
,
false
/* flyView */
,
_offlineVehicle
));
QCOMPARE
(
simpleItems
->
count
(),
1
);
_validateItem
(
simpleItems
->
value
<
FixedWingLandingComplexItem
*>
(
0
));
// Reset
simpleItems
->
deleteLater
();
rgMissionItems
.
clear
();
// Check for no stop camera actions
_fwItem
->
stopTakingPhotos
()
->
setRawValue
(
false
);
_fwItem
->
stopTakingVideo
()
->
setRawValue
(
false
);
_fwItem
->
appendMissionItems
(
rgMissionItems
,
this
);
simpleItems
=
new
QmlObjectListModel
(
this
);
for
(
MissionItem
*
item
:
rgMissionItems
)
{
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
false
/* flyView */
,
simpleItems
);
simpleItem
->
missionItem
()
=
*
item
;
simpleItems
->
append
(
simpleItem
);
}
QVERIFY
(
FixedWingLandingComplexItem
::
scanForItem
(
simpleItems
,
false
/* flyView */
,
_offlineVehicle
));
QCOMPARE
(
simpleItems
->
count
(),
1
);
_validateItem
(
simpleItems
->
value
<
FixedWingLandingComplexItem
*>
(
0
));
// Reset
simpleItems
->
deleteLater
();
rgMissionItems
.
clear
();
}
void
FWLandingPatternTest
::
_testDirty
(
void
)
{
_fwItem
->
setDirty
(
true
);
QVERIFY
(
_fwItem
->
dirty
());
QVERIFY
(
_multiSpy
->
checkOnlySignalByMask
(
dirtyChangedMask
));
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
_fwItem
->
setDirty
(
false
);
_multiSpy
->
clearAllSignals
();
// These facts should set dirty when changed
QList
<
Fact
*>
rgFacts
;
rgFacts
<<
_fwItem
->
loiterAltitude
()
<<
_fwItem
->
landingHeading
()
<<
_fwItem
->
loiterRadius
()
<<
_fwItem
->
landingAltitude
()
<<
_fwItem
->
landingDistance
()
<<
_fwItem
->
glideSlope
()
<<
_fwItem
->
stopTakingPhotos
()
<<
_fwItem
->
stopTakingVideo
();
for
(
Fact
*
fact
:
rgFacts
)
{
qDebug
()
<<
fact
->
name
();
QVERIFY
(
!
_fwItem
->
dirty
());
if
(
fact
->
typeIsBool
())
{
fact
->
setRawValue
(
!
fact
->
rawValue
().
toBool
());
}
else
{
fact
->
setRawValue
(
fact
->
rawValue
().
toDouble
()
+
1
);
}
QVERIFY
(
_multiSpy
->
checkSignalByMask
(
dirtyChangedMask
));
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
_fwItem
->
setDirty
(
false
);
_multiSpy
->
clearAllSignals
();
}
rgFacts
.
clear
();
// These bool properties should set dirty when changed
QList
<
const
char
*>
rgBoolNames
;
rgBoolNames
<<
"valueSetIsDistance"
<<
"loiterClockwise"
<<
"altitudesAreRelative"
;
const
QMetaObject
*
metaObject
=
_fwItem
->
metaObject
();
for
(
const
char
*
boolName
:
rgBoolNames
)
{
qDebug
()
<<
boolName
;
QVERIFY
(
!
_fwItem
->
dirty
());
QMetaProperty
boolProp
=
metaObject
->
property
(
metaObject
->
indexOfProperty
(
boolName
));
QVERIFY
(
boolProp
.
write
(
_fwItem
,
!
boolProp
.
read
(
_fwItem
).
toBool
()));
QVERIFY
(
_multiSpy
->
checkSignalByMask
(
dirtyChangedMask
));
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
_fwItem
->
setDirty
(
false
);
_multiSpy
->
clearAllSignals
();
}
rgFacts
.
clear
();
// These coordinates should set dirty when changed
QVERIFY
(
!
_fwItem
->
dirty
());
_fwItem
->
setLoiterCoordinate
(
_fwItem
->
loiterCoordinate
().
atDistanceAndAzimuth
(
1
,
0
));
QVERIFY
(
_multiSpy
->
checkSignalByMask
(
dirtyChangedMask
));
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
_fwItem
->
setDirty
(
false
);
_multiSpy
->
clearAllSignals
();
QVERIFY
(
!
_fwItem
->
dirty
());
_fwItem
->
setLoiterCoordinate
(
_fwItem
->
landingCoordinate
().
atDistanceAndAzimuth
(
1
,
0
));
QVERIFY
(
_multiSpy
->
checkSignalByMask
(
dirtyChangedMask
));
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
_fwItem
->
setDirty
(
false
);
_multiSpy
->
clearAllSignals
();
}
void
FWLandingPatternTest
::
_testSaveLoad
(
void
)
{
QJsonArray
items
;
_fwItem
->
save
(
items
);
QString
errorString
;
FixedWingLandingComplexItem
*
newItem
=
new
FixedWingLandingComplexItem
(
_offlineVehicle
,
false
/* flyView */
,
this
/* parent */
);
bool
success
=
newItem
->
load
(
items
[
0
].
toObject
(),
10
,
errorString
);
if
(
!
success
)
{
qDebug
()
<<
errorString
;
}
QVERIFY
(
success
);
QVERIFY
(
errorString
.
isEmpty
());
_validateItem
(
newItem
);
newItem
->
deleteLater
();
}
void
FWLandingPatternTest
::
_validateItem
(
FixedWingLandingComplexItem
*
newItem
)
{
QVERIFY
(
newItem
);
QVERIFY
(
fuzzyCompareLatLon
(
newItem
->
loiterCoordinate
(),
_fwItem
->
loiterCoordinate
()));
QVERIFY
(
fuzzyCompareLatLon
(
newItem
->
loiterTangentCoordinate
(),
_fwItem
->
loiterTangentCoordinate
()));
QVERIFY
(
fuzzyCompareLatLon
(
newItem
->
landingCoordinate
(),
_fwItem
->
landingCoordinate
()));
QCOMPARE
(
newItem
->
stopTakingPhotos
()
->
rawValue
().
toBool
(),
_fwItem
->
stopTakingPhotos
()
->
rawValue
().
toBool
());
QCOMPARE
(
newItem
->
stopTakingVideo
()
->
rawValue
().
toBool
(),
_fwItem
->
stopTakingVideo
()
->
rawValue
().
toBool
());
QCOMPARE
(
newItem
->
loiterAltitude
()
->
rawValue
().
toInt
(),
_fwItem
->
loiterAltitude
()
->
rawValue
().
toInt
());
QCOMPARE
(
newItem
->
loiterRadius
()
->
rawValue
().
toInt
(),
_fwItem
->
loiterRadius
()
->
rawValue
().
toInt
());
QCOMPARE
(
newItem
->
landingAltitude
()
->
rawValue
().
toInt
(),
_fwItem
->
landingAltitude
()
->
rawValue
().
toInt
());
QCOMPARE
(
newItem
->
landingHeading
()
->
rawValue
().
toInt
(),
_fwItem
->
landingHeading
()
->
rawValue
().
toInt
());
QCOMPARE
(
newItem
->
landingDistance
()
->
rawValue
().
toInt
(),
_fwItem
->
landingDistance
()
->
rawValue
().
toInt
());
QCOMPARE
(
newItem
->
glideSlope
()
->
rawValue
().
toInt
(),
_fwItem
->
glideSlope
()
->
rawValue
().
toInt
());
QCOMPARE
(
newItem
->
_valueSetIsDistance
,
_fwItem
->
_valueSetIsDistance
);
QCOMPARE
(
newItem
->
_loiterClockwise
,
_fwItem
->
_loiterClockwise
);
QCOMPARE
(
newItem
->
_altitudesAreRelative
,
_fwItem
->
_altitudesAreRelative
);
QCOMPARE
(
newItem
->
_landingCoordSet
,
_fwItem
->
_landingCoordSet
);
}
src/MissionManager/FWLandingPatternTest.h
0 → 100644
View file @
92e7bf38
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "UnitTest.h"
#include "FixedWingLandingComplexItem.h"
#include "MultiSignalSpy.h"
class
FWLandingPatternTest
:
public
UnitTest
{
Q_OBJECT
public:
FWLandingPatternTest
(
void
);
void
init
(
void
)
override
;
void
cleanup
(
void
)
override
;
private
slots
:
void
_testDirty
(
void
);
void
_testItemCount
(
void
);
void
_testDefaults
(
void
);
void
_testAppendSectionItems
(
void
);
void
_testSaveLoad
(
void
);
private:
void
_validateItem
(
FixedWingLandingComplexItem
*
newItem
);
enum
{
dirtyChangedIndex
=
0
,
maxSignalIndex
,
};
enum
{
dirtyChangedMask
=
1
<<
dirtyChangedIndex
,
};
static
const
size_t
cSignals
=
maxSignalIndex
;
const
char
*
rgSignals
[
cSignals
];
Vehicle
*
_offlineVehicle
;
FixedWingLandingComplexItem
*
_fwItem
;
MultiSignalSpy
*
_multiSpy
;
SimpleMissionItem
*
_validStopVideoItem
;
SimpleMissionItem
*
_validStopDistanceItem
;
SimpleMissionItem
*
_validStopTimeItem
;
};
src/MissionManager/FixedWingLandingComplexItem.cc
View file @
92e7bf38
This diff is collapsed.
Click to expand it.
src/MissionManager/FixedWingLandingComplexItem.h
View file @
92e7bf38
...
...
@@ -17,6 +17,8 @@
Q_DECLARE_LOGGING_CATEGORY
(
FixedWingLandingComplexItemLog
)
class
FWLandingPatternTest
;
class
FixedWingLandingComplexItem
:
public
ComplexMissionItem
{
Q_OBJECT
...
...
@@ -33,6 +35,8 @@ public:
Q_PROPERTY
(
Fact
*
glideSlope
READ
glideSlope
CONSTANT
)
Q_PROPERTY
(
bool
loiterClockwise
MEMBER
_loiterClockwise
NOTIFY
loiterClockwiseChanged
)
Q_PROPERTY
(
bool
altitudesAreRelative
MEMBER
_altitudesAreRelative
NOTIFY
altitudesAreRelativeChanged
)
Q_PROPERTY
(
Fact
*
stopTakingPhotos
READ
stopTakingPhotos
CONSTANT
)
Q_PROPERTY
(
Fact
*
stopTakingVideo
READ
stopTakingVideo
CONSTANT
)
Q_PROPERTY
(
QGeoCoordinate
loiterCoordinate
READ
loiterCoordinate
WRITE
setLoiterCoordinate
NOTIFY
loiterCoordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
loiterTangentCoordinate
READ
loiterTangentCoordinate
NOTIFY
loiterTangentCoordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
landingCoordinate
READ
landingCoordinate
WRITE
setLandingCoordinate
NOTIFY
landingCoordinateChanged
)
...
...
@@ -44,6 +48,8 @@ public:
Fact
*
landingDistance
(
void
)
{
return
&
_landingDistanceFact
;
}
Fact
*
landingHeading
(
void
)
{
return
&
_landingHeadingFact
;
}
Fact
*
glideSlope
(
void
)
{
return
&
_glideSlopeFact
;
}
Fact
*
stopTakingPhotos
(
void
)
{
return
&
_stopTakingPhotosFact
;
}
Fact
*
stopTakingVideo
(
void
)
{
return
&
_stopTakingVideoFact
;
}
QGeoCoordinate
landingCoordinate
(
void
)
const
{
return
_landingCoordinate
;
}
QGeoCoordinate
loiterCoordinate
(
void
)
const
{
return
_loiterCoordinate
;
}
QGeoCoordinate
loiterTangentCoordinate
(
void
)
const
{
return
_loiterTangentCoordinate
;
}
...
...
@@ -54,6 +60,10 @@ public:
/// Scans the loaded items for a landing pattern complex item
static
bool
scanForItem
(
QmlObjectListModel
*
visualItems
,
bool
flyView
,
Vehicle
*
vehicle
);
static
MissionItem
*
createDoLandStartItem
(
int
seqNum
,
QObject
*
parent
);
static
MissionItem
*
createLoiterToAltItem
(
int
seqNum
,
bool
altRel
,
double
loiterRaidus
,
double
lat
,
double
lon
,
double
alt
,
QObject
*
parent
);
static
MissionItem
*
createLandItem
(
int
seqNum
,
bool
altRel
,
double
lat
,
double
lon
,
double
alt
,
QObject
*
parent
);
// Overrides from ComplexMissionItem
double
complexDistance
(
void
)
const
final
;
...
...
@@ -98,6 +108,8 @@ public:
static
const
char
*
landingHeadingName
;
static
const
char
*
landingAltitudeName
;
static
const
char
*
glideSlopeName
;
static
const
char
*
stopTakingPhotosName
;
static
const
char
*
stopTakingVideoName
;
signals:
void
loiterCoordinateChanged
(
QGeoCoordinate
coordinate
);
...
...
@@ -118,6 +130,7 @@ private slots:
double
_headingToMathematicAngle
(
double
heading
);
void
_setDirty
(
void
);
void
_glideSlopeChanged
(
void
);
void
_signalLastSequenceNumberChanged
(
void
);
private:
QPointF
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
);
...
...
@@ -139,6 +152,8 @@ private:
Fact
_landingHeadingFact
;
Fact
_landingAltitudeFact
;
Fact
_glideSlopeFact
;
Fact
_stopTakingPhotosFact
;
Fact
_stopTakingVideoFact
;
bool
_loiterClockwise
;
bool
_altitudesAreRelative
;
...
...
@@ -151,11 +166,15 @@ private:
static
const
char
*
_jsonLandingCoordinateKey
;
static
const
char
*
_jsonValueSetIsDistanceKey
;
static
const
char
*
_jsonAltitudesAreRelativeKey
;
static
const
char
*
_jsonStopTakingPhotosKey
;
static
const
char
*
_jsonStopTakingVideoKey
;
// Only in older file formats
static
const
char
*
_jsonLandingAltitudeRelativeKey
;
static
const
char
*
_jsonLoiterAltitudeRelativeKey
;
static
const
char
*
_jsonFallRateKey
;
friend
FWLandingPatternTest
;
};
#endif
src/MissionManager/SectionTest.cc
View file @
92e7bf38
...
...
@@ -54,21 +54,6 @@ void SectionTest::_createSpy(Section* section, MultiSignalSpy** sectionSpy)
*
sectionSpy
=
spy
;
}
void
SectionTest
::
_missionItemsEqual
(
MissionItem
&
actual
,
MissionItem
&
expected
)
{
QCOMPARE
(
actual
.
command
(),
expected
.
command
());
QCOMPARE
(
actual
.
frame
(),
expected
.
frame
());
QCOMPARE
(
actual
.
autoContinue
(),
expected
.
autoContinue
());
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param1
(),
expected
.
param1
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param2
(),
expected
.
param2
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param3
(),
expected
.
param3
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param4
(),
expected
.
param4
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param5
(),
expected
.
param5
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param6
(),
expected
.
param6
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param7
(),
expected
.
param7
()));
}
void
SectionTest
::
_commonScanTest
(
Section
*
section
)
{
QCOMPARE
(
section
->
available
(),
true
);
...
...
src/MissionManager/SectionTest.h
View file @
92e7bf38
...
...
@@ -25,7 +25,6 @@ public:
protected:
void
_createSpy
(
Section
*
section
,
MultiSignalSpy
**
sectionSpy
);
void
_missionItemsEqual
(
MissionItem
&
actual
,
MissionItem
&
expected
);
void
_commonScanTest
(
Section
*
section
);
enum
{
...
...
src/PlanView/FWLandingPatternEditor.qml
View file @
92e7bf38
...
...
@@ -16,6 +16,7 @@ import QGroundControl 1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Vehicle
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FactSystem
1.0
import
QGroundControl
.
FactControls
1.0
import
QGroundControl
.
Palette
1.0
...
...
@@ -163,6 +164,34 @@ Rectangle {
visible
:
QGroundControl
.
corePlugin
.
options
.
showMissionAbsoluteAltitude
||
!
missionItem
.
altitudesAreRelative
onClicked
:
missionItem
.
altitudesAreRelative
=
checked
}
SectionHeader
{
id
:
cameraSection
text
:
qsTr
(
"
Camera
"
)
}
Column
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
cameraSection
.
checked
Item
{
width
:
1
;
height
:
_spacer
}
FactCheckBox
{
text
:
_stopTakingPhotos
.
shortDescription
fact
:
_stopTakingPhotos
property
Fact
_stopTakingPhotos
:
missionItem
.
stopTakingPhotos
}
FactCheckBox
{
text
:
_stopTakingVideo
.
shortDescription
fact
:
_stopTakingVideo
property
Fact
_stopTakingVideo
:
missionItem
.
stopTakingVideo
}
}
}
Column
{
...
...
src/qgcunittest/UnitTest.cc
View file @
92e7bf38
...
...
@@ -535,3 +535,23 @@ void UnitTest::changeFactValue(Fact* fact,double increment)
fact
->
setRawValue
(
fact
->
rawValue
().
toDouble
()
+
increment
);
}
}
void
UnitTest
::
_missionItemsEqual
(
MissionItem
&
actual
,
MissionItem
&
expected
)
{
QCOMPARE
(
static_cast
<
int
>
(
actual
.
command
()),
static_cast
<
int
>
(
expected
.
command
()));
QCOMPARE
(
static_cast
<
int
>
(
actual
.
frame
()),
static_cast
<
int
>
(
expected
.
frame
()));
QCOMPARE
(
actual
.
autoContinue
(),
expected
.
autoContinue
());
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param1
(),
expected
.
param1
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param2
(),
expected
.
param2
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param3
(),
expected
.
param3
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param4
(),
expected
.
param4
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param5
(),
expected
.
param5
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param6
(),
expected
.
param6
()));
QVERIFY
(
UnitTest
::
doubleNaNCompare
(
actual
.
param7
(),
expected
.
param7
()));
}
bool
UnitTest
::
fuzzyCompareLatLon
(
const
QGeoCoordinate
&
coord1
,
const
QGeoCoordinate
&
coord2
)
{
return
coord1
.
distanceTo
(
coord2
)
<
1.0
;
}
src/qgcunittest/UnitTest.h
View file @
92e7bf38
...
...
@@ -25,6 +25,7 @@
#include "QGCMAVLink.h"
#include "LinkInterface.h"
#include "Fact.h"
#include "MissionItem.h"
#define UT_REGISTER_TEST(className) static UnitTestWrapper<className> className(#className);
...
...
@@ -101,6 +102,10 @@ public:
/// @param increment 0 use standard increment, other increment by specified amount if double value
void
changeFactValue
(
Fact
*
fact
,
double
increment
=
0
);
/// Returns true is the position of the two coordinates is less then a meter from each other.
/// Does not check altitude.
static
bool
fuzzyCompareLatLon
(
const
QGeoCoordinate
&
coord1
,
const
QGeoCoordinate
&
coord2
);
protected
slots
:
// These are all pure virtuals to force the derived class to implement each one and in turn
...
...
@@ -119,6 +124,7 @@ protected:
void
_disconnectMockLink
(
void
);
void
_createMainWindow
(
void
);
void
_closeMainWindow
(
bool
cancelExpected
=
false
);
void
_missionItemsEqual
(
MissionItem
&
actual
,
MissionItem
&
expected
);
LinkManager
*
_linkManager
;
MockLink
*
_mockLink
;
...
...
src/qgcunittest/UnitTestList.cc
View file @
92e7bf38
...
...
@@ -44,6 +44,7 @@
#include "CorridorScanComplexItemTest.h"
#include "TransectStyleComplexItemTest.h"
#include "CameraCalcTest.h"
#include "FWLandingPatternTest.h"
UT_REGISTER_TEST
(
FactSystemTestGeneric
)
UT_REGISTER_TEST
(
FactSystemTestPX4
)
...
...
@@ -75,6 +76,7 @@ UT_REGISTER_TEST(CorridorScanComplexItemTest)
UT_REGISTER_TEST
(
TransectStyleComplexItemTest
)
UT_REGISTER_TEST
(
QGCMapPolylineTest
)
UT_REGISTER_TEST
(
CameraCalcTest
)
UT_REGISTER_TEST
(
FWLandingPatternTest
)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
...
...
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