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
1dffdbf1
Commit
1dffdbf1
authored
Mar 20, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Waypoint now supports camera section
parent
2f1e631c
Changes
29
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
29 changed files
with
843 additions
and
507 deletions
+843
-507
qgroundcontrol.pro
qgroundcontrol.pro
+2
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+2
-0
CameraSection.qml
src/MissionEditor/CameraSection.qml
+108
-0
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+1
-1
MissionSettingsEditor.qml
src/MissionEditor/MissionSettingsEditor.qml
+2
-92
SectionHeader.qml
src/MissionEditor/SectionHeader.qml
+6
-1
SimpleItemEditor.qml
src/MissionEditor/SimpleItemEditor.qml
+6
-0
CameraSection.FactMetaData.json
src/MissionManager/CameraSection.FactMetaData.json
+48
-0
CameraSection.cc
src/MissionManager/CameraSection.cc
+256
-0
CameraSection.h
src/MissionManager/CameraSection.h
+103
-0
ComplexMissionItem.h
src/MissionManager/ComplexMissionItem.h
+1
-10
FixedWingLandingComplexItem.cc
src/MissionManager/FixedWingLandingComplexItem.cc
+8
-12
FixedWingLandingComplexItem.h
src/MissionManager/FixedWingLandingComplexItem.h
+2
-2
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+1
-0
MissionCommandUIInfo.cc
src/MissionManager/MissionCommandUIInfo.cc
+29
-3
MissionCommandUIInfo.h
src/MissionManager/MissionCommandUIInfo.h
+9
-1
MissionController.cc
src/MissionManager/MissionController.cc
+43
-38
MissionController.h
src/MissionManager/MissionController.h
+1
-0
MissionSettings.FactMetaData.json
src/MissionManager/MissionSettings.FactMetaData.json
+0
-46
MissionSettingsComplexItem.cc
src/MissionManager/MissionSettingsComplexItem.cc
+59
-223
MissionSettingsComplexItem.h
src/MissionManager/MissionSettingsComplexItem.h
+17
-45
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+88
-10
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+21
-2
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+9
-12
SurveyMissionItem.h
src/MissionManager/SurveyMissionItem.h
+2
-2
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+10
-1
QGCComboBox.qml
src/QmlControls/QGCComboBox.qml
+8
-6
QGroundControl.Controls.qmldir
src/QmlControls/QGroundControl.Controls.qmldir
+1
-0
arrow-down.png
src/QmlControls/arrow-down.png
+0
-0
No files found.
qgroundcontrol.pro
View file @
1dffdbf1
...
...
@@ -449,6 +449,7 @@ HEADERS += \
src/JsonHelper.h \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/CameraSection.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/FixedWingLandingComplexItem.h \
src/MissionManager/GeoFenceController.h \
...
...
@@ -626,6 +627,7 @@ SOURCES += \
src/Joystick/JoystickManager.cc \
src/JsonHelper.cc \
src/LogCompressor.cc \
src/MissionManager/CameraSection.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/FixedWingLandingComplexItem.cc \
src/MissionManager/GeoFenceController.cc \
...
...
qgroundcontrol.qrc
View file @
1dffdbf1
...
...
@@ -49,6 +49,7 @@
<file alias="PX4FlowSensor.qml">src/VehicleSetup/PX4FlowSensor.qml</file>
<file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
<file alias="QGroundControl/Controls/AppMessages.qml">src/QmlControls/AppMessages.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/MissionEditor/CameraSection.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
<file alias="QGroundControl/Controls/DropButton.qml">src/QmlControls/DropButton.qml</file>
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
...
...
@@ -192,6 +193,7 @@
<file alias="RallyPoint.FactMetaData.json">src/MissionManager/RallyPoint.FactMetaData.json</file>
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="CameraSection.FactMetaData.json">src/MissionManager/CameraSection.FactMetaData.json</file>
<file alias="MissionSettings.FactMetaData.json">src/MissionManager/MissionSettings.FactMetaData.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
...
...
src/MissionEditor/CameraSection.qml
0 → 100644
View file @
1dffdbf1
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtQuick
.
Layouts
1.2
import
QGroundControl
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FactControls
1.0
import
QGroundControl
.
Palette
1.0
// Camera section for mission item editors
Column
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
property
alias
exclusiveGroup
:
cameraSectionHeader
.
exclusiveGroup
property
alias
showSpacer
:
cameraSectionHeader
.
showSpacer
property
alias
checked
:
cameraSectionHeader
.
checked
property
var
_camera
:
missionItem
.
cameraSection
property
real
_fieldWidth
:
ScreenTools
.
defaultFontPixelWidth
*
16
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
SectionHeader
{
id
:
cameraSectionHeader
text
:
qsTr
(
"
Camera
"
)
checked
:
false
}
Column
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
cameraSectionHeader
.
checked
FactComboBox
{
id
:
cameraActionCombo
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
fact
:
_camera
.
cameraAction
indexModel
:
false
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
cameraActionCombo
.
currentIndex
==
1
QGCLabel
{
text
:
qsTr
(
"
Time
"
)
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
_camera
.
cameraPhotoIntervalTime
Layout.preferredWidth
:
_fieldWidth
}
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
cameraActionCombo
.
currentIndex
==
2
QGCLabel
{
text
:
qsTr
(
"
Distance
"
)
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
_camera
.
cameraPhotoIntervalDistance
Layout.preferredWidth
:
_fieldWidth
}
}
GridLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
columnSpacing
:
ScreenTools
.
defaultFontPixelWidth
/
2
rowSpacing
:
0
columns
:
3
Item
{
width
:
1
;
height
:
1
}
QGCLabel
{
text
:
qsTr
(
"
Pitch
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Yaw
"
)
}
QGCCheckBox
{
id
:
gimbalCheckBox
text
:
qsTr
(
"
Gimbal
"
)
checked
:
_camera
.
specifyGimbal
onClicked
:
_camera
.
specifyGimbal
=
checked
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
_camera
.
gimbalPitch
implicitWidth
:
ScreenTools
.
defaultFontPixelWidth
*
9
enabled
:
gimbalCheckBox
.
checked
}
FactTextField
{
fact
:
_camera
.
gimbalYaw
implicitWidth
:
ScreenTools
.
defaultFontPixelWidth
*
9
enabled
:
gimbalCheckBox
.
checked
}
}
}
}
src/MissionEditor/MissionEditor.qml
View file @
1dffdbf1
...
...
@@ -579,7 +579,7 @@ QGCView {
spacing
:
_margin
/
2
orientation
:
ListView
.
Vertical
model
:
missionController
.
visualItems
cacheBuffer
:
height
*
2
cacheBuffer
:
Math
.
max
(
height
*
2
,
0
)
clip
:
true
currentIndex
:
_currentMissionIndex
highlightMoveDuration
:
250
...
...
src/MissionEditor/MissionSettingsEditor.qml
View file @
1dffdbf1
...
...
@@ -19,12 +19,6 @@ Rectangle {
visible
:
missionItem
.
isCurrentItem
radius
:
_radius
ExclusiveGroup
{
id
:
sectionHeaderExclusiverGroup
}
property
ExclusiveGroup
sectionHeaderGroup
:
ScreenTools
.
isShortScreen
?
sectionHeaderExclusiverGroup
:
null
Loader
{
id
:
deferedload
active
:
valuesRect
.
visible
...
...
@@ -64,7 +58,6 @@ Rectangle {
id
:
plannedHomePositionSection
text
:
qsTr
(
"
Planned Home Position
"
)
showSpacer
:
false
exclusiveGroup
:
sectionHeaderGroup
}
Column
{
...
...
@@ -125,7 +118,6 @@ Rectangle {
text
:
qsTr
(
"
Vehicle Info
"
)
visible
:
_multipleFirmware
&&
_showOfflineEditingCombos
checked
:
false
exclusiveGroup
:
sectionHeaderGroup
}
GridLayout
{
...
...
@@ -183,7 +175,6 @@ Rectangle {
id
:
missionDefaultsSectionHeader
text
:
qsTr
(
"
Mission Defaults
"
)
checked
:
false
exclusiveGroup
:
sectionHeaderGroup
}
Column
{
...
...
@@ -233,89 +224,8 @@ Rectangle {
*/
}
SectionHeader
{
id
:
cameraSectionHeader
text
:
qsTr
(
"
Camera
"
)
checked
:
false
exclusiveGroup
:
sectionHeaderGroup
}
Column
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
cameraSectionHeader
.
checked
FactComboBox
{
id
:
cameraActionCombo
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
fact
:
missionItem
.
cameraAction
indexModel
:
false
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
cameraActionCombo
.
currentIndex
==
1
QGCLabel
{
text
:
qsTr
(
"
Time
"
)
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
missionItem
.
cameraPhotoIntervalTime
Layout.preferredWidth
:
_fieldWidth
}
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
cameraActionCombo
.
currentIndex
==
2
QGCLabel
{
text
:
qsTr
(
"
Distance
"
)
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
missionItem
.
cameraPhotoIntervalDistance
Layout.preferredWidth
:
_fieldWidth
}
}
GridLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
columnSpacing
:
0
rowSpacing
:
0
columns
:
3
Item
{
width
:
1
;
height
:
1
}
QGCLabel
{
text
:
qsTr
(
"
Pitch
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Yaw
"
)
}
QGCCheckBox
{
id
:
gimbalCheckBox
text
:
qsTr
(
"
Gimbal
"
)
checked
:
missionItem
.
specifyGimbal
onClicked
:
missionItem
.
specifyGimbal
=
checked
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
missionItem
.
gimbalPitch
implicitWidth
:
ScreenTools
.
defaultFontPixelWidth
*
9
enabled
:
gimbalCheckBox
.
checked
}
FactTextField
{
fact
:
missionItem
.
gimbalYaw
implicitWidth
:
ScreenTools
.
defaultFontPixelWidth
*
9
enabled
:
gimbalCheckBox
.
checked
}
}
CameraSection
{
checked
:
missionItem
.
cameraSection
.
settingsSpecified
}
QGCLabel
{
...
...
src/MissionEditor/SectionHeader.qml
View file @
1dffdbf1
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtQuick
.
Layouts
1.2
import
QtGraphicalEffects
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Palette
1.0
...
...
@@ -41,10 +42,14 @@ QGCMouseArea {
id
:
label
Layout.fillWidth
:
true
Image
{
QGCColoredImage
{
id
:
image
width
:
label
.
height
/
2
height
:
width
anchors.right
:
parent
.
right
anchors.verticalCenter
:
parent
.
verticalCenter
source
:
"
/qmlimages/arrow-down.png
"
color
:
qgcPal
.
text
visible
:
!
_root
.
checked
}
}
...
...
src/MissionEditor/SimpleItemEditor.qml
View file @
1dffdbf1
...
...
@@ -27,6 +27,7 @@ Rectangle {
anchors.left
:
valuesRect
.
left
anchors.right
:
valuesRect
.
right
anchors.top
:
valuesRect
.
top
sourceComponent
:
Component
{
Item
{
id
:
valuesItem
...
...
@@ -114,6 +115,11 @@ Rectangle {
fact
:
object
}
}
CameraSection
{
checked
:
missionItem
.
cameraSection
.
settingsSpecified
visible
:
missionItem
.
cameraSection
.
available
}
}
// Column
}
// Item
}
// Component
...
...
src/MissionManager/CameraSection.FactMetaData.json
0 → 100644
View file @
1dffdbf1
[
{
"name"
:
"CameraAction"
,
"shortDescription"
:
"Specify whether the camera should take photos or video"
,
"type"
:
"uint32"
,
"enumStrings"
:
"Continue current action,Take photos (time),Take photos (distance),Take video"
,
"enumValues"
:
"0,1,2,3"
,
"defaultValue"
:
0
},
{
"name"
:
"CameraPhotoIntervalDistance"
,
"shortDescription"
:
"Specify the distance between each photo"
,
"type"
:
"double"
,
"units"
:
"m"
,
"min"
:
0
,
"decimalPlaces"
:
1
,
"defaultValue"
:
1
},
{
"name"
:
"CameraPhotoIntervalTime"
,
"shortDescription"
:
"Specify the time between each photo"
,
"type"
:
"uint32"
,
"units"
:
"secs"
,
"min"
:
1
,
"decimalPlaces"
:
0
,
"defaultValue"
:
10
},
{
"name"
:
"GimbalPitch"
,
"shortDescription"
:
"Gimbal pitch rotation."
,
"type"
:
"double"
,
"units"
:
"deg"
,
"min"
:
0.0
,
"max"
:
360.0
,
"decimalPlaces"
:
0
,
"defaultValue"
:
0
},
{
"name"
:
"GimbalYaw"
,
"shortDescription"
:
"Gimbal yaw rotation."
,
"type"
:
"double"
,
"units"
:
"deg"
,
"min"
:
0.0
,
"max"
:
360.0
,
"decimalPlaces"
:
0
,
"defaultValue"
:
0
}
]
src/MissionManager/CameraSection.cc
0 → 100644
View file @
1dffdbf1
This diff is collapsed.
Click to expand it.
src/MissionManager/CameraSection.h
0 → 100644
View file @
1dffdbf1
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef CameraSection_H
#define CameraSection_H
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
Q_DECLARE_LOGGING_CATEGORY
(
CameraSectionLog
)
class
CameraSection
:
public
QObject
{
Q_OBJECT
public:
CameraSection
(
QObject
*
parent
=
NULL
);
enum
CameraAction
{
CameraActionNone
,
TakePhotosIntervalTime
,
TakePhotoIntervalDistance
,
TakeVideo
};
Q_ENUMS
(
CameraAction
)
Q_PROPERTY
(
bool
available
READ
available
WRITE
setAvailable
NOTIFY
availableChanged
)
Q_PROPERTY
(
bool
settingsSpecified
MEMBER
_settingsSpecified
NOTIFY
settingsSpecifiedChanged
)
Q_PROPERTY
(
bool
specifyGimbal
READ
specifyGimbal
WRITE
setSpecifyGimbal
NOTIFY
specifyGimbalChanged
)
Q_PROPERTY
(
Fact
*
gimbalPitch
READ
gimbalPitch
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalYaw
READ
gimbalYaw
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraAction
READ
cameraAction
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalTime
READ
cameraPhotoIntervalTime
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalDistance
READ
cameraPhotoIntervalDistance
CONSTANT
)
bool
available
(
void
)
const
{
return
_available
;
}
void
setAvailable
(
bool
available
);
bool
specifyGimbal
(
void
)
const
{
return
_specifyGimbal
;
}
Fact
*
gimbalYaw
(
void
)
{
return
&
_gimbalYawFact
;
}
Fact
*
gimbalPitch
(
void
)
{
return
&
_gimbalPitchFact
;
}
Fact
*
cameraAction
(
void
)
{
return
&
_cameraActionFact
;
}
Fact
*
cameraPhotoIntervalTime
(
void
)
{
return
&
_cameraPhotoIntervalTimeFact
;
}
Fact
*
cameraPhotoIntervalDistance
(
void
)
{
return
&
_cameraPhotoIntervalDistanceFact
;
}
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex Index to start scanning from
/// @return true: camera section found
bool
scanForCameraSection
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
/// Appends the mission items associated with this section
/// @param items List to append to
/// @param missionItemParent QObject parent for created MissionItems
/// @param nextSequenceNumber Sequence number for first item
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
nextSequenceNumber
);
void
setSpecifyGimbal
(
bool
specifyGimbal
);
bool
dirty
(
void
)
const
{
return
_dirty
;
}
void
setDirty
(
bool
dirty
);
/// Returns the number of mission items represented by this section.
/// Signals: missionItemCountChanged on change
int
missionItemCount
(
void
)
const
;
signals:
void
availableChanged
(
bool
available
);
void
settingsSpecifiedChanged
(
bool
settingsSpecified
);
void
dirtyChanged
(
bool
dirty
);
bool
specifyGimbalChanged
(
bool
specifyGimbal
);
void
missionItemCountChanged
(
int
missionItemCount
);
private
slots
:
void
_setDirty
(
void
);
void
_setDirtyAndUpdateMissionItemCount
(
void
);
private:
bool
_available
;
bool
_settingsSpecified
;
bool
_specifyGimbal
;
Fact
_gimbalYawFact
;
Fact
_gimbalPitchFact
;
Fact
_cameraActionFact
;
Fact
_cameraPhotoIntervalDistanceFact
;
Fact
_cameraPhotoIntervalTimeFact
;
bool
_dirty
;
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_gimbalPitchName
;
static
const
char
*
_gimbalYawName
;
static
const
char
*
_cameraActionName
;
static
const
char
*
_cameraPhotoIntervalDistanceName
;
static
const
char
*
_cameraPhotoIntervalTimeName
;
};
#endif
src/MissionManager/ComplexMissionItem.h
View file @
1dffdbf1
...
...
@@ -21,19 +21,11 @@ public:
const
ComplexMissionItem
&
operator
=
(
const
ComplexMissionItem
&
other
);
Q_PROPERTY
(
int
lastSequenceNumber
READ
lastSequenceNumber
NOTIFY
lastSequenceNumberChanged
)
Q_PROPERTY
(
double
complexDistance
READ
complexDistance
NOTIFY
complexDistanceChanged
)
/// @return The distance covered the complex mission item in meters.
virtual
double
complexDistance
(
void
)
const
=
0
;
/// @return The last sequence number used by this item. Takes into account child items of the complex item
virtual
int
lastSequenceNumber
(
void
)
const
=
0
;
/// Returns the mission items associated with the complex item. Caller is responsible for freeing. Calling
/// delete on returned QmlObjectListModel will free all memory including internal items.
virtual
QmlObjectListModel
*
getMissionItems
(
void
)
const
=
0
;
/// Load the complex mission item from Json
/// @param complexObject Complex mission item json object
/// @param sequenceNumber Sequence number for first MISSION_ITEM in survey
...
...
@@ -53,8 +45,7 @@ public:
static
const
char
*
jsonComplexItemTypeKey
;
signals:
void
lastSequenceNumberChanged
(
int
lastSequenceNumber
);
void
complexDistanceChanged
(
double
complexDistance
);
void
complexDistanceChanged
(
double
complexDistance
);
};
#endif
src/MissionManager/FixedWingLandingComplexItem.cc
View file @
1dffdbf1
...
...
@@ -105,7 +105,7 @@ void FixedWingLandingComplexItem::setDirty(bool dirty)
}
}
void
FixedWingLandingComplexItem
::
save
(
QJsonArray
&
missionItems
)
const
void
FixedWingLandingComplexItem
::
save
(
QJsonArray
&
missionItems
)
{
QJsonObject
saveObject
;
...
...
@@ -203,10 +203,8 @@ bool FixedWingLandingComplexItem::specifiesCoordinate(void) const
return
true
;
}
QmlObjectListModel
*
FixedWingLandingComplexItem
::
getMissionItems
(
void
)
const
void
FixedWingLandingComplexItem
::
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
{
QmlObjectListModel
*
pMissionItems
=
new
QmlObjectListModel
;
int
seqNum
=
_sequenceNumber
;
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
// sequence number
...
...
@@ -215,8 +213,8 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
// param 1-7
true
,
// autoContinue
false
,
// isCurrentItem
pMissionItems
);
// parent - allow delete on pMissionItems to delete everthing
pMissionItems
->
append
(
item
);
missionItemParent
);
items
.
append
(
item
);
float
loiterRadius
=
_loiterRadiusFact
.
rawValue
().
toDouble
()
*
(
_loiterClockwise
?
1.0
:
-
1.0
);
item
=
new
MissionItem
(
seqNum
++
,
...
...
@@ -231,8 +229,8 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const
_loiterAltitudeFact
.
rawValue
().
toDouble
(),
true
,
// autoContinue
false
,
// isCurrentItem
pMissionItems
);
// parent - allow delete on pMissionItems to delete everthing
pMissionItems
->
append
(
item
);
missionItemParent
);
items
.
append
(
item
);
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_NAV_LAND
,
...
...
@@ -243,10 +241,8 @@ QmlObjectListModel* FixedWingLandingComplexItem::getMissionItems(void) const
_landingAltitudeFact
.
rawValue
().
toDouble
(),
true
,
// autoContinue
false
,
// isCurrentItem
pMissionItems
);
// parent - allow delete on pMissionItems to delete everthing
pMissionItems
->
append
(
item
);
return
pMissionItems
;
missionItemParent
);
items
.
append
(
item
);
}
double
FixedWingLandingComplexItem
::
complexDistance
(
void
)
const
...
...
src/MissionManager/FixedWingLandingComplexItem.h
View file @
1dffdbf1
...
...
@@ -53,7 +53,6 @@ public:
double
complexDistance
(
void
)
const
final
;
int
lastSequenceNumber
(
void
)
const
final
;
QmlObjectListModel
*
getMissionItems
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
void
setCruiseSpeed
(
double
cruiseSpeed
)
final
;
...
...
@@ -72,6 +71,7 @@ public:
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_landingCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
flightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
...
...
@@ -80,7 +80,7 @@ public:
void
setDirty
(
bool
dirty
)
final
;
void
setCoordinate
(
const
QGeoCoordinate
&
coordinate
)
final
{
setLoiterCoordinate
(
coordinate
);
}
void
setSequenceNumber
(
int
sequenceNumber
)
final
;
void
save
(
QJsonArray
&
missionItems
)
const
final
;
void
save
(
QJsonArray
&
missionItems
)
final
;
static
const
char
*
jsonComplexItemTypeValue
;
...
...
src/MissionManager/MavCmdInfoCommon.json
View file @
1dffdbf1
...
...
@@ -32,6 +32,7 @@
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"cameraSection"
:
true
,
"param1"
:
{
"label"
:
"Hold"
,
"units"
:
"secs"
,
...
...
src/MissionManager/MissionCommandUIInfo.cc
View file @
1dffdbf1
...
...
@@ -35,8 +35,10 @@ const char* MissionCommandUIInfo::_paramRemoveJsonKey = "paramRemove";
const
char
*
MissionCommandUIInfo
::
_rawNameJsonKey
=
"rawName"
;
const
char
*
MissionCommandUIInfo
::
_standaloneCoordinateJsonKey
=
"standaloneCoordinate"
;
const
char
*
MissionCommandUIInfo
::
_specifiesCoordinateJsonKey
=
"specifiesCoordinate"
;
const
char
*
MissionCommandUIInfo
::
_specifiesAltitudeOnlyJsonKey
=
"specifiesAltitudeOnly"
;
const
char
*
MissionCommandUIInfo
::
_unitsJsonKey
=
"units"
;
const
char
*
MissionCommandUIInfo
::
_commentJsonKey
=
"comment"
;
const
char
*
MissionCommandUIInfo
::
_cameraSectionJsonKey
=
"cameraSection"
;
const
char
*
MissionCommandUIInfo
::
_advancedCategory
=
"Advanced"
;
MissionCmdParamInfo
::
MissionCmdParamInfo
(
QObject
*
parent
)
...
...
@@ -143,7 +145,7 @@ bool MissionCommandUIInfo::isStandaloneCoordinate(void) const
}
}
bool
MissionCommandUIInfo
::
specifiesCoordinate
(
void
)
const
bool
MissionCommandUIInfo
::
specifiesCoordinate
(
void
)
const
{
if
(
_infoMap
.
contains
(
_specifiesCoordinateJsonKey
))
{
return
_infoMap
[
_specifiesCoordinateJsonKey
].
toBool
();
...
...
@@ -152,6 +154,24 @@ bool MissionCommandUIInfo::specifiesCoordinate (void) const
}
}
bool
MissionCommandUIInfo
::
specifiesAltitudeOnly
(
void
)
const
{
if
(
_infoMap
.
contains
(
_specifiesAltitudeOnlyJsonKey
))
{
return
_infoMap
[
_specifiesAltitudeOnlyJsonKey
].
toBool
();
}
else
{
return
false
;
}
}
bool
MissionCommandUIInfo
::
cameraSection
(
void
)
const
{
if
(
_infoMap
.
contains
(
_cameraSectionJsonKey
))
{
return
_infoMap
[
_cameraSectionJsonKey
].
toBool
();
}
else
{
return
false
;
}
}
void
MissionCommandUIInfo
::
_overrideInfo
(
MissionCommandUIInfo
*
uiInfo
)
{
// Override info values
...
...
@@ -187,7 +207,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QStringList
allKeys
;
allKeys
<<
_idJsonKey
<<
_rawNameJsonKey
<<
_friendlyNameJsonKey
<<
_descriptionJsonKey
<<
_standaloneCoordinateJsonKey
<<
_specifiesCoordinateJsonKey
<<
_friendlyEditJsonKey
<<
_param1JsonKey
<<
_param2JsonKey
<<
_param3JsonKey
<<
_param4JsonKey
<<
_param5JsonKey
<<
_param6JsonKey
<<
_param7JsonKey
<<
_paramRemoveJsonKey
<<
_categoryJsonKey
;
<<
_paramRemoveJsonKey
<<
_categoryJsonKey
<<
_cameraSectionJsonKey
<<
_specifiesAltitudeOnlyJsonKey
;
// Look for unknown keys in top level object
foreach
(
const
QString
&
key
,
jsonObject
.
keys
())
{
...
...
@@ -219,7 +239,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QList
<
QJsonValue
::
Type
>
types
;
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
String
<<
QJsonValue
::
String
;
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
;
if
(
!
JsonHelper
::
validateKeyTypes
(
jsonObject
,
allKeys
,
types
,
internalError
))
{
errorString
=
_loadErrorString
(
internalError
);
return
false
;
...
...
@@ -247,9 +267,15 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
if
(
jsonObject
.
contains
(
_specifiesCoordinateJsonKey
))
{
_infoMap
[
_specifiesCoordinateJsonKey
]
=
jsonObject
.
value
(
_specifiesCoordinateJsonKey
).
toVariant
();
}
if
(
jsonObject
.
contains
(
_specifiesAltitudeOnlyJsonKey
))
{
_infoMap
[
_specifiesAltitudeOnlyJsonKey
]
=
jsonObject
.
value
(
_specifiesAltitudeOnlyJsonKey
).
toBool
();
}
if
(
jsonObject
.
contains
(
_friendlyEditJsonKey
))
{
_infoMap
[
_friendlyEditJsonKey
]
=
jsonObject
.
value
(
_friendlyEditJsonKey
).
toVariant
();
}
if
(
jsonObject
.
contains
(
_cameraSectionJsonKey
))
{
_infoMap
[
_cameraSectionJsonKey
]
=
jsonObject
.
value
(
_cameraSectionJsonKey
).
toVariant
();
}
if
(
jsonObject
.
contains
(
_paramRemoveJsonKey
))
{
QStringList
indexList
=
jsonObject
.
value
(
_paramRemoveJsonKey
).
toString
().
split
(
QStringLiteral
(
","
));
foreach
(
const
QString
&
indexString
,
indexList
)
{
...
...
src/MissionManager/MissionCommandUIInfo.h
View file @
1dffdbf1
...
...
@@ -90,8 +90,10 @@ private:
/// friendlyName string rawName Short description of command
/// description string Long description of command
/// specifiesCoordinate bool false true: Command specifies a lat/lon/alt coordinate
/// specifiesAltitudeOnly bool false true: Command specifies an altitude only (no coordinate)
/// standaloneCoordinate bool false true: Vehicle does not fly through coordinate associated with command (exampl: ROI)
/// friendlyEdit bool false true: Command supports friendly editing dialog, false: Command supports 'Show all values" style editing only
/// cameraSection bool false true: Camera section of additional settings is added to editor
/// category string Advanced Category which this command belongs to
/// paramRemove string Used by an override to remove params, example: "1,3" will remove params 1 and 3 on the override
/// param[1-7] object MissionCommandParamInfo object
...
...
@@ -112,7 +114,9 @@ public:
Q_PROPERTY
(
QString
rawName
READ
rawName
CONSTANT
)
Q_PROPERTY
(
bool
isStandaloneCoordinate
READ
isStandaloneCoordinate
CONSTANT
)
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
CONSTANT
)
Q_PROPERTY
(
bool
specifiesAltitudeOnly
READ
specifiesAltitudeOnly
CONSTANT
)
Q_PROPERTY
(
int
command
READ
intCommand
CONSTANT
)
Q_PROPERTY
(
bool
cameraSection
READ
cameraSection
CONSTANT
)
MAV_CMD
command
(
void
)
const
{
return
_command
;
}
int
intCommand
(
void
)
const
{
return
(
int
)
_command
;
}
...
...
@@ -124,6 +128,8 @@ public:
QString
rawName
(
void
)
const
;
bool
isStandaloneCoordinate
(
void
)
const
;
bool
specifiesCoordinate
(
void
)
const
;
bool
specifiesAltitudeOnly
(
void
)
const
;
bool
cameraSection
(
void
)
const
;
/// Load the data in the object from the specified json
/// @param jsonObject Json object to load from
...
...
@@ -178,8 +184,10 @@ private:
static
const
char
*
_rawNameJsonKey
;
static
const
char
*
_standaloneCoordinateJsonKey
;
static
const
char
*
_specifiesCoordinateJsonKey
;
static
const
char
*
_specifiesAltitudeOnlyJsonKey
;