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
e3566933
Commit
e3566933
authored
Jan 10, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Mission Settings replaces Planned Home Position
- Shot Interval in Survey - Much change to time/distance calc
parent
63aecd5d
Changes
18
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
18 changed files
with
606 additions
and
406 deletions
+606
-406
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+1
-2
MissionItemEditor.qml
src/MissionEditor/MissionItemEditor.qml
+11
-8
MissionItemStatus.qml
src/MissionEditor/MissionItemStatus.qml
+30
-87
MissionSettingsEditor.qml
src/MissionEditor/MissionSettingsEditor.qml
+196
-0
SurveyItemEditor.qml
src/MissionEditor/SurveyItemEditor.qml
+5
-2
ComplexMissionItem.h
src/MissionManager/ComplexMissionItem.h
+3
-0
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+1
-1
MissionController.cc
src/MissionManager/MissionController.cc
+174
-103
MissionController.h
src/MissionManager/MissionController.h
+42
-20
PlanElementController.cc
src/MissionManager/PlanElementController.cc
+2
-0
PlanElementController.h
src/MissionManager/PlanElementController.h
+5
-0
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+25
-5
SurveyMissionItem.h
src/MissionManager/SurveyMissionItem.h
+7
-1
QGroundControlQmlGlobal.json
src/QmlControls/QGroundControlQmlGlobal.json
+2
-2
Vehicle.cc
src/Vehicle/Vehicle.cc
+70
-69
Vehicle.h
src/Vehicle/Vehicle.h
+25
-21
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+6
-85
No files found.
qgroundcontrol.qrc
View file @
e3566933
...
...
@@ -32,6 +32,7 @@
<file alias="MainWindowNative.qml">src/ui/MainWindowNative.qml</file>
<file alias="MavlinkSettings.qml">src/ui/preferences/MavlinkSettings.qml</file>
<file alias="MissionEditor.qml">src/MissionEditor/MissionEditor.qml</file>
<file alias="MissionSettingsEditor.qml">src/MissionEditor/MissionSettingsEditor.qml</file>
<file alias="MockLink.qml">src/ui/preferences/MockLink.qml</file>
<file alias="MockLinkSettings.qml">src/ui/preferences/MockLinkSettings.qml</file>
<file alias="MultiVehicleView.qml">src/MultiVehicle/MultiVehicleView.qml</file>
...
...
src/MissionEditor/MissionEditor.qml
View file @
e3566933
...
...
@@ -944,9 +944,8 @@ QGCView {
missionItems
:
missionController
.
visualItems
expandedWidth
:
missionItemEditor
.
x
-
(
ScreenTools
.
defaultFontPixelWidth
*
2
)
missionDistance
:
missionController
.
missionDistance
missionTime
:
missionController
.
missionTime
missionMaxTelemetry
:
missionController
.
missionMaxTelemetry
cruiseDistance
:
missionController
.
cruiseDistance
hoverDistance
:
missionController
.
hoverDistance
visible
:
_editingLayer
==
_layerMission
&&
!
ScreenTools
.
isShortScreen
}
}
// FlightMap
...
...
src/MissionEditor/MissionItemEditor.qml
View file @
e3566933
...
...
@@ -26,8 +26,9 @@ Rectangle {
signal
insert
signal
moveHomeToMapCenter
property
bool
_currentItem
:
missionItem
.
isCurrentItem
property
color
_outerTextColor
:
_currentItem
?
"
black
"
:
qgcPal
.
text
property
bool
_currentItem
:
missionItem
.
isCurrentItem
property
color
_outerTextColor
:
_currentItem
?
"
black
"
:
qgcPal
.
text
property
bool
_noMissionItemsAdded
:
ListView
.
view
.
model
.
count
==
1
readonly
property
real
_editFieldWidth
:
Math
.
min
(
width
-
_margin
*
2
,
ScreenTools
.
defaultFontPixelWidth
*
12
)
readonly
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
...
...
@@ -38,7 +39,6 @@ Rectangle {
colorGroupEnabled
:
enabled
}
MouseArea
{
anchors.fill
:
parent
visible
:
!
missionItem
.
isCurrentItem
...
...
@@ -121,7 +121,6 @@ Rectangle {
anchors.rightMargin
:
ScreenTools
.
defaultFontPixelWidth
anchors.left
:
label
.
right
anchors.top
:
parent
.
top
//anchors.right: hamburger.left
visible
:
missionItem
.
sequenceNumber
!=
0
&&
missionItem
.
isCurrentItem
&&
!
missionItem
.
rawEdit
&&
missionItem
.
isSimpleItem
text
:
missionItem
.
commandName
...
...
@@ -133,7 +132,7 @@ Rectangle {
}
}
onClicked
:
qgcView
.
showDialog
(
commandDialog
,
qsTr
(
"
Select Mission Command
"
),
qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Cancel
)
onClicked
:
qgcView
.
showDialog
(
commandDialog
,
qsTr
(
"
Select Mission Command
"
),
qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Cancel
)
}
QGCLabel
{
...
...
@@ -141,7 +140,7 @@ Rectangle {
visible
:
missionItem
.
sequenceNumber
==
0
||
!
missionItem
.
isCurrentItem
||
!
missionItem
.
isSimpleItem
verticalAlignment
:
Text
.
AlignVCenter
text
:
missionItem
.
sequenceNumber
==
0
?
qsTr
(
"
Planned Home Position
"
)
:
qsTr
(
"
Mission Settings
"
)
:
(
missionItem
.
isSimpleItem
?
missionItem
.
commandName
:
qsTr
(
"
Survey
"
))
color
:
_outerTextColor
}
...
...
@@ -153,8 +152,12 @@ Rectangle {
anchors.left
:
parent
.
left
anchors.top
:
commandPicker
.
bottom
height
:
item
?
item
.
height
:
0
source
:
missionItem
.
isSimpleItem
?
"
qrc:/qml/SimpleItemEditor.qml
"
:
"
qrc:/qml/SurveyItemEditor.qml
"
onLoaded
:
{
item
.
visible
=
Qt
.
binding
(
function
()
{
return
_currentItem
;
})
}
source
:
missionItem
.
sequenceNumber
==
0
?
"
qrc:/qml/MissionSettingsEditor.qml
"
:
(
missionItem
.
isSimpleItem
?
"
qrc:/qml/SimpleItemEditor.qml
"
:
"
qrc:/qml/SurveyItemEditor.qml
"
)
onLoaded
:
{
item
.
visible
=
Qt
.
binding
(
function
()
{
return
_currentItem
;
})
}
property
real
availableWidth
:
_root
.
width
-
(
_margin
*
2
)
///< How wide the editor should be
property
var
editorRoot
:
_root
}
...
...
src/MissionEditor/MissionItemStatus.qml
View file @
e3566933
...
...
@@ -20,20 +20,6 @@ import QGroundControl.FactSystem 1.0
import
QGroundControl
.
FactControls
1.0
Rectangle
{
readonly
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
Fact
_offlineEditingVehicleType
:
QGroundControl
.
offlineEditingVehicleType
property
Fact
_offlineEditingCruiseSpeed
:
QGroundControl
.
offlineEditingCruiseSpeed
property
Fact
_offlineEditingHoverSpeed
:
QGroundControl
.
offlineEditingHoverSpeed
property
var
currentMissionItem
///< Mission item to display status for
property
var
missionItems
///< List of all available mission items
property
real
expandedWidth
///< Width of control when expanded
property
real
missionDistance
property
real
missionMaxTelemetry
property
real
cruiseDistance
property
real
hoverDistance
width
:
_expanded
?
expandedWidth
:
_collapsedWidth
height
:
Math
.
max
(
valueGrid
.
height
,
valueMissionGrid
.
height
)
+
(
_margins
*
2
)
radius
:
ScreenTools
.
defaultFontPixelWidth
*
0.5
...
...
@@ -41,42 +27,35 @@ Rectangle {
opacity
:
0.80
clip
:
true
readonly
property
real
margins
:
ScreenTools
.
defaultFontPixelWidth
property
real
_collapsedWidth
:
valueGrid
.
width
+
(
margins
*
2
)
property
bool
_expanded
:
true
property
real
_distance
:
_statusValid
?
_currentMissionItem
.
distance
:
0
property
real
_altDifference
:
_statusValid
?
_currentMissionItem
.
altDifference
:
0
property
real
_gradient
:
_statusValid
&&
_currentMissionItem
.
distance
>
0
?
Math
.
atan
(
_currentMissionItem
.
altDifference
/
_currentMissionItem
.
distance
)
:
0
property
real
_gradientPercent
:
isNaN
(
_gradient
)
?
0
:
_gradient
*
100
property
real
_azimuth
:
_statusValid
?
_currentMissionItem
.
azimuth
:
-
1
property
real
_missionDistance
:
_missionValid
?
missionDistance
:
0
property
real
_missionMaxTelemetry
:
_missionValid
?
missionMaxTelemetry
:
0
property
real
_missionTime
:
_missionValid
&&
_missionSpeed
>
0
?
(
_isVTOL
?
_hoverTime
+
_cruiseTime
:
_missionDistance
/
_missionSpeed
)
:
0
property
real
_hoverDistance
:
_missionValid
?
hoverDistance
:
0
property
real
_cruiseDistance
:
_missionValid
?
cruiseDistance
:
0
property
real
_hoverTime
:
_missionValid
&&
_offlineEditingHoverSpeed
.
value
>
0
?
_hoverDistance
/
_offlineEditingHoverSpeed
.
value
:
0
property
real
_cruiseTime
:
_missionValid
&&
_offlineEditingCruiseSpeed
.
value
>
0
?
_cruiseDistance
/
_offlineEditingCruiseSpeed
.
value
:
0
property
bool
_statusValid
:
currentMissionItem
!=
undefined
property
bool
_vehicleValid
:
_activeVehicle
!=
undefined
property
bool
_missionValid
:
missionItems
!=
undefined
property
bool
_currentSurvey
:
_statusValid
?
_currentMissionItem
.
commandName
==
"
Survey
"
:
false
property
bool
_isVTOL
:
_vehicleValid
?
_activeVehicle
.
vtol
:
_offlineEditingVehicleType
.
enumStringValue
==
"
VTOL
"
//hardcoded
property
real
_missionSpeed
:
_offlineEditingVehicleType
.
enumStringValue
==
"
Fixedwing
"
?
_offlineEditingCruiseSpeed
.
value
:
_offlineEditingHoverSpeed
.
value
property
string
_distanceText
:
_statusValid
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_distance
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
"
"
property
string
_altText
:
_statusValid
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_altDifference
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
"
"
property
string
_gradientText
:
_statusValid
?
_gradientPercent
.
toFixed
(
0
)
+
"
%
"
:
"
"
property
string
_azimuthText
:
_statusValid
?
Math
.
round
(
_azimuth
)
:
"
"
property
string
_missionDistanceText
:
_missionValid
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_missionDistance
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
"
"
property
string
_missionTimeText
:
_missionValid
?
Number
(
_missionTime
/
60
).
toFixed
(
1
)
+
"
min
"
:
"
"
property
string
_missionMaxTelemetryText
:
_missionValid
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_missionMaxTelemetry
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
"
"
property
string
_hoverDistanceText
:
_missionValid
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_hoverDistance
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
"
"
property
string
_cruiseDistanceText
:
_missionValid
?
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_cruiseDistance
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
:
"
"
property
string
_hoverTimeText
:
_missionValid
?
_hoverTime
.
toFixed
(
0
)
+
"
s
"
:
"
"
property
string
_cruiseTimeText
:
_missionValid
?
_cruiseTime
.
toFixed
(
0
)
+
"
s
"
:
"
"
property
var
currentMissionItem
///< Mission item to display status for
property
var
missionItems
///< List of all available mission items
property
real
expandedWidth
///< Width of control when expanded
property
real
missionDistance
///< Total mission distance
property
real
missionTime
///< Total mission time
property
real
missionMaxTelemetry
property
real
_collapsedWidth
:
valueGrid
.
width
+
(
_margins
*
2
)
property
bool
_expanded
:
true
property
bool
_statusValid
:
currentMissionItem
!=
undefined
property
bool
_missionValid
:
missionItems
!=
undefined
property
real
_distance
:
_statusValid
?
_currentMissionItem
.
distance
:
NaN
property
real
_altDifference
:
_statusValid
?
_currentMissionItem
.
altDifference
:
NaN
property
real
_gradient
:
_statusValid
&&
_currentMissionItem
.
distance
>
0
?
Math
.
atan
(
_currentMissionItem
.
altDifference
/
_currentMissionItem
.
distance
)
:
NaN
property
real
_gradientPercent
:
isNaN
(
_gradient
)
?
NaN
:
_gradient
*
100
property
real
_azimuth
:
_statusValid
?
_currentMissionItem
.
azimuth
:
NaN
property
real
_missionDistance
:
_missionValid
?
missionDistance
:
NaN
property
real
_missionMaxTelemetry
:
_missionValid
?
missionMaxTelemetry
:
NaN
property
real
_missionTime
:
_missionValid
?
missionTime
:
NaN
property
string
_distanceText
:
isNaN
(
_distance
)
?
"
-.-
"
:
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_distance
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
property
string
_altDifferenceText
:
isNaN
(
_altDifference
)
?
"
-.-
"
:
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_altDifference
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
property
string
_gradientText
:
isNaN
(
_gradient
)
?
"
-.-
"
:
_gradientPercent
.
toFixed
(
0
)
+
"
%
"
property
string
_azimuthText
:
isNaN
(
_azimuth
)
?
"
-.-
"
:
Math
.
round
(
_azimuth
)
property
string
_missionDistanceText
:
isNaN
(
_missionDistance
)
?
"
-.-
"
:
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_missionDistance
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
property
string
_missionTimeText
:
isNaN
(
_missionTime
)
?
"
-.-
"
:
Number
(
_missionTime
/
60
).
toFixed
(
1
)
+
"
min
"
property
string
_missionMaxTelemetryText
:
isNaN
(
_missionMaxTelemetry
)
?
"
-.-
"
:
QGroundControl
.
metersToAppSettingsDistanceUnits
(
_missionMaxTelemetry
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsDistanceUnitsString
readonly
property
real
_margins
:
ScreenTools
.
defaultFontPixelWidth
...
...
@@ -103,7 +82,7 @@ Rectangle {
QGCLabel
{
text
:
_distanceText
}
QGCLabel
{
text
:
qsTr
(
"
Alt diff:
"
)
}
QGCLabel
{
text
:
_altText
}
QGCLabel
{
text
:
_alt
Difference
Text
}
QGCLabel
{
text
:
qsTr
(
"
Gradient:
"
)
}
QGCLabel
{
text
:
_gradientText
}
...
...
@@ -166,42 +145,6 @@ Rectangle {
QGCLabel
{
text
:
qsTr
(
"
Max telem dist:
"
)
}
QGCLabel
{
text
:
_missionMaxTelemetryText
}
QGCLabel
{
text
:
qsTr
(
"
Hover distance:
"
)
visible
:
_isVTOL
}
QGCLabel
{
text
:
_hoverDistanceText
visible
:
_isVTOL
}
QGCLabel
{
text
:
qsTr
(
"
Cruise distance:
"
)
visible
:
_isVTOL
}
QGCLabel
{
text
:
_cruiseDistanceText
visible
:
_isVTOL
}
QGCLabel
{
text
:
qsTr
(
"
Hover time:
"
)
visible
:
_isVTOL
}
QGCLabel
{
text
:
_hoverTimeText
visible
:
_isVTOL
}
QGCLabel
{
text
:
qsTr
(
"
Cruise time:
"
)
visible
:
_isVTOL
}
QGCLabel
{
text
:
_cruiseTimeText
visible
:
_isVTOL
}
}
}
}
src/MissionEditor/MissionSettingsEditor.qml
0 → 100644
View file @
e3566933
import
QtQuick
2.5
import
QtQuick
.
Controls
1.2
import
QtQuick
.
Layouts
1.2
import
QGroundControl
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Vehicle
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FactControls
1.0
import
QGroundControl
.
Palette
1.0
// Editor for Mission Settings
Rectangle
{
id
:
valuesRect
width
:
availableWidth
height
:
deferedload
.
status
==
Loader
.
Ready
?
(
visible
?
deferedload
.
item
.
height
:
0
)
:
0
color
:
qgcPal
.
windowShadeDark
visible
:
missionItem
.
isCurrentItem
radius
:
_radius
Loader
{
id
:
deferedload
active
:
valuesRect
.
visible
asynchronous
:
true
anchors.margins
:
_margin
anchors.left
:
valuesRect
.
left
anchors.right
:
valuesRect
.
right
anchors.top
:
valuesRect
.
top
sourceComponent
:
Component
{
Item
{
id
:
valuesItem
height
:
valuesColumn
.
height
+
(
_margin
*
2
)
property
var
_missionVehicle
:
missionController
.
vehicle
property
bool
_offlineEditing
:
_missionVehicle
.
isOfflineEditingVehicle
property
bool
_showOfflineEditingCombos
:
_offlineEditing
&&
_noMissionItemsAdded
property
bool
_showCruiseSpeed
:
!
_missionVehicle
.
multiRotor
property
bool
_showHoverSpeed
:
_missionVehicle
.
multiRotor
||
missionController
.
vehicle
.
vtol
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware:
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle:
"
)
QGCPalette
{
id
:
qgcPal
}
Column
{
id
:
valuesColumn
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.top
:
parent
.
top
spacing
:
_margin
QGCLabel
{
text
:
qsTr
(
"
Planned Home Position:
"
)
}
Rectangle
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
height
:
1
color
:
qgcPal
.
text
}
Repeater
{
model
:
missionItem
.
textFieldFacts
Item
{
width
:
valuesColumn
.
width
height
:
textField
.
height
QGCLabel
{
id
:
textFieldLabel
anchors.baseline
:
textField
.
baseline
text
:
object
.
name
}
FactTextField
{
id
:
textField
anchors.right
:
parent
.
right
width
:
_editFieldWidth
showUnits
:
true
fact
:
object
visible
:
!
_root
.
readOnly
}
FactLabel
{
anchors.baseline
:
textFieldLabel
.
baseline
anchors.right
:
parent
.
right
fact
:
object
visible
:
_root
.
readOnly
}
}
}
QGCButton
{
text
:
qsTr
(
"
Move Home to map center
"
)
visible
:
missionItem
.
homePosition
onClicked
:
editorRoot
.
moveHomeToMapCenter
()
anchors.horizontalCenter
:
parent
.
horizontalCenter
}
QGCLabel
{
width
:
parent
.
width
wrapMode
:
Text
.
WordWrap
font.pointSize
:
ScreenTools
.
smallFontPointSize
text
:
qsTr
(
"
Note: Planned home position for mission display only. Actual home position set by vehicle at flight time.
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Vehicle Info:
"
)
}
Rectangle
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
height
:
1
color
:
qgcPal
.
text
}
GridLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
columnSpacing
:
ScreenTools
.
defaultFontPixelWidth
rowSpacing
:
columnSpacing
columns
:
2
QGCLabel
{
text
:
_firmwareLabel
visible
:
_showOfflineEditingCombos
}
FactComboBox
{
Layout.fillWidth
:
true
fact
:
QGroundControl
.
offlineEditingFirmwareType
indexModel
:
false
visible
:
_showOfflineEditingCombos
}
QGCLabel
{
text
:
_firmwareLabel
visible
:
!
_showOfflineEditingCombos
}
QGCLabel
{
text
:
_missionVehicle
.
firmwareTypeString
visible
:
!
_showOfflineEditingCombos
}
QGCLabel
{
text
:
_vehicleLabel
visible
:
_showOfflineEditingCombos
}
FactComboBox
{
id
:
offlineVehicleCombo
Layout.fillWidth
:
true
fact
:
QGroundControl
.
offlineEditingVehicleType
indexModel
:
false
visible
:
_showOfflineEditingCombos
}
QGCLabel
{
text
:
_vehicleLabel
visible
:
!
_showOfflineEditingCombos
}
QGCLabel
{
text
:
_missionVehicle
.
vehicleTypeString
visible
:
!
_showOfflineEditingCombos
}
QGCLabel
{
Layout.row
:
2
text
:
qsTr
(
"
Cruise speed:
"
)
visible
:
_showCruiseSpeed
}
FactTextField
{
Layout.fillWidth
:
true
fact
:
QGroundControl
.
offlineEditingCruiseSpeed
visible
:
_showCruiseSpeed
}
QGCLabel
{
Layout.row
:
3
text
:
qsTr
(
"
Hover speed:
"
)
visible
:
_showHoverSpeed
}
FactTextField
{
Layout.fillWidth
:
true
fact
:
QGroundControl
.
offlineEditingHoverSpeed
visible
:
_showHoverSpeed
}
}
// GridLayout
QGCLabel
{
width
:
parent
.
width
wrapMode
:
Text
.
WordWrap
font.pointSize
:
ScreenTools
.
smallFontPointSize
text
:
qsTr
(
"
Note: Speeds are planned speeds only for time calculations. Actual vehicle will not be affected.
"
)
}
}
// Column
}
// Item
}
// Component
}
// Loader
}
// Rectangle
src/MissionEditor/SurveyItemEditor.qml
View file @
e3566933
...
...
@@ -579,14 +579,17 @@ Rectangle {
}
Grid
{
columns
:
2
spacing
:
ScreenTools
.
defaultFontPixelWidth
columns
:
2
columnSpacing
:
ScreenTools
.
defaultFontPixelWidth
QGCLabel
{
text
:
qsTr
(
"
Survey area:
"
)
}
QGCLabel
{
text
:
QGroundControl
.
squareMetersToAppSettingsAreaUnits
(
missionItem
.
coveredArea
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsAreaUnitsString
}
QGCLabel
{
text
:
qsTr
(
"
# shots:
"
)
}
QGCLabel
{
text
:
missionItem
.
cameraShots
}
QGCLabel
{
text
:
qsTr
(
"
Shot interval:
"
)
}
QGCLabel
{
text
:
missionItem
.
timeBetweenShots
.
toFixed
(
1
)
+
"
"
+
qsTr
(
"
secs
"
)}
}
}
}
src/MissionManager/ComplexMissionItem.h
View file @
e3566933
...
...
@@ -46,6 +46,9 @@ public:
/// @return the greatest distance from any point of the complex item to some coordinate
virtual
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
=
0
;
/// Informs the complex item of the cruise speed it will fly at
virtual
void
setCruiseSpeed
(
double
cruiseSpeed
)
=
0
;
/// This mission item attribute specifies the type of the complex item.
static
const
char
*
jsonComplexItemTypeKey
;
...
...
src/MissionManager/MavCmdInfoCommon.json
View file @
e3566933
...
...
@@ -5,7 +5,7 @@
"mavCmdInfo"
:
[
{
"comment"
:
"MAV_CMD_NAV_LAST: Used for
fake
home position waypoint"
,
"comment"
:
"MAV_CMD_NAV_LAST: Used for
mission settings / planned
home position waypoint"
,
"id"
:
95
,
"rawName"
:
"HomeRaw"
,
"friendlyName"
:
"Home Position"
,
...
...
src/MissionManager/MissionController.cc
View file @
e3566933
This diff is collapsed.
Click to expand it.
src/MissionManager/MissionController.h
View file @
e3566933
...
...
@@ -34,15 +34,18 @@ public:
MissionController
(
QObject
*
parent
=
NULL
);
~
MissionController
();
Q_PROPERTY
(
QGeoCoordinate
plannedHomePosition
READ
plannedHomePosition
NOTIFY
plannedHomePositionChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
visualItems
READ
visualItems
NOTIFY
visualItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
complexVisualItems
READ
complexVisualItems
NOTIFY
complexVisualItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
waypointLines
READ
waypointLines
NOTIFY
waypointLinesChanged
)
Q_PROPERTY
(
double
missionDistance
READ
missionDistance
NOTIFY
missionDistanceChanged
)
Q_PROPERTY
(
double
missionMaxTelemetry
READ
missionMaxTelemetry
NOTIFY
missionMaxTelemetryChanged
)
Q_PROPERTY
(
double
cruiseDistance
READ
cruiseDistance
NOTIFY
cruiseDistanceChanged
)
Q_PROPERTY
(
double
hoverDistance
READ
hoverDistance
NOTIFY
hoverDistanceChanged
)
Q_PROPERTY
(
QGeoCoordinate
plannedHomePosition
READ
plannedHomePosition
NOTIFY
plannedHomePositionChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
visualItems
READ
visualItems
NOTIFY
visualItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
complexVisualItems
READ
complexVisualItems
NOTIFY
complexVisualItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
waypointLines
READ
waypointLines
NOTIFY
waypointLinesChanged
)
Q_PROPERTY
(
double
missionDistance
READ
missionDistance
NOTIFY
missionDistanceChanged
)
Q_PROPERTY
(
double
missionTime
READ
missionTime
NOTIFY
missionTimeChanged
)
Q_PROPERTY
(
double
missionHoverDistance
READ
missionHoverDistance
NOTIFY
missionHoverDistanceChanged
)
Q_PROPERTY
(
double
missionCruiseDistance
READ
missionCruiseDistance
NOTIFY
missionCruiseDistanceChanged
)
Q_PROPERTY
(
double
missionHoverTime
READ
missionHoverTime
NOTIFY
missionHoverTimeChanged
)
Q_PROPERTY
(
double
missionCruiseTime
READ
missionCruiseTime
NOTIFY
missionCruiseTimeChanged
)
Q_PROPERTY
(
double
missionMaxTelemetry
READ
missionMaxTelemetry
NOTIFY
missionMaxTelemetryChanged
)
Q_INVOKABLE
void
removeMissionItem
(
int
index
);
...
...
@@ -80,15 +83,14 @@ public:
QmlObjectListModel
*
waypointLines
(
void
)
{
return
&
_waypointLines
;
}
double
missionDistance
(
void
)
const
{
return
_missionDistance
;
}
double
missionTime
(
void
)
const
{
return
_missionTime
;
}
double
missionHoverDistance
(
void
)
const
{
return
_missionHoverDistance
;
}
double
missionHoverTime
(
void
)
const
{
return
_missionHoverTime
;
}
double
missionCruiseDistance
(
void
)
const
{
return
_missionCruiseDistance
;
}
double
missionCruiseTime
(
void
)
const
{
return
_missionCruiseTime
;
}
double
missionMaxTelemetry
(
void
)
const
{
return
_missionMaxTelemetry
;
}
double
cruiseDistance
(
void
)
const
{
return
_cruiseDistance
;
}
double
hoverDistance
(
void
)
const
{
return
_hoverDistance
;
}
void
setMissionDistance
(
double
missionDistance
);
void
setMissionMaxTelemetry
(
double
missionMaxTelemetry
);
void
setCruiseDistance
(
double
cruiseDistance
);
void
setHoverDistance
(
double
hoverDistance
);
double
cruiseSpeed
(
void
)
const
;
double
hoverSpeed
(
void
)
const
;
signals:
void
plannedHomePositionChanged
(
QGeoCoordinate
plannedHomePosition
);
...
...
@@ -97,9 +99,16 @@ signals:
void
waypointLinesChanged
(
void
);
void
newItemsFromVehicle
(
void
);
void
missionDistanceChanged
(
double
missionDistance
);
void
missionTimeChanged
(
void
);
void
missionHoverDistanceChanged
(
double
missionHoverDistance
);
void
missionHoverTimeChanged
(
void
);
void
missionCruiseDistanceChanged
(
double
missionCruiseDistance
);
void
missionCruiseTimeChanged
(
void
);
void
missionMaxTelemetryChanged
(
double
missionMaxTelemetry
);
void
cruiseDistanceChanged
(
double
cruiseDistance
);
void
hoverDistanceChanged
(
double
hoverDistance
);
void
cruiseSpeedChanged
(
double
cruiseSpeed
);
void
hoverSpeedChanged
(
double
hoverSpeed
);
private
slots
:
void
_newMissionItemsAvailableFromVehicle
();
...
...
@@ -123,7 +132,7 @@ private:
void
_deinitVisualItem
(
VisualMissionItem
*
item
);
void
_setupActiveVehicle
(
Vehicle
*
activeVehicle
,
bool
forceLoadFromVehicle
);
static
void
_calcPrevWaypointValues
(
double
homeAlt
,
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
prevItem
,
double
*
azimuth
,
double
*
distance
,
double
*
altDifference
);
static
void
_calcHomeDist
(
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
homeItem
,
double
*
distance
);
static
double
_calcDistanceToHome
(
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
homeItem
);
bool
_findLastAltitude
(
double
*
lastAltitude
,
MAV_FRAME
*
frame
);
bool
_findLastAcceptanceRadius
(
double
*
lastAcceptanceRadius
);
void
_addPlannedHomePosition
(
QmlObjectListModel
*
visualItems
,
bool
addToCenter
);
...
...
@@ -134,6 +143,13 @@ private:
bool
_loadJsonMissionFileV2
(
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
bool
_loadTextMissionFile
(
QTextStream
&
stream
,
QmlObjectListModel
*
visualItems
,
QString
&
errorString
);
int
_nextSequenceNumber
(
void
);
void
_setMissionDistance
(
double
missionDistance
);
void
_setMissionTime
(
double
missionTime
);
void
_setMissionHoverDistance
(
double
missionHoverDistance
);
void
_setMissionHoverTime
(
double
missionHoverTime
);
void
_setMissionCruiseDistance
(
double
missionCruiseDistance
);
void
_setMissionCruiseTime
(
double
missionCruiseTime
);
void
_setMissionMaxTelemetry
(
double
missionMaxTelemetry
);
// Overrides from PlanElementController
void
_activeVehicleBeingRemoved
(
void
)
final
;
...
...
@@ -148,13 +164,19 @@ private:
bool
_missionItemsRequested
;
bool
_queuedSend
;
double
_missionDistance
;
double
_missionTime
;
double
_missionHoverDistance
;
double
_missionHoverTime
;
double
_missionCruiseDistance
;
double
_missionCruiseTime
;
double
_missionMaxTelemetry
;
double
_cruiseDistance
;
double
_hoverDistance
;
static
const
char
*
_settingsGroup
;
static
const
char
*
_jsonFileTypeValue
;
static
const
char
*
_jsonFirmwareTypeKey
;
static
const
char
*
_jsonVehicleTypeKey
;
static
const
char
*
_jsonCruiseSpeedKey
;
static
const
char
*
_jsonHoverSpeedKey
;
static
const
char
*
_jsonItemsKey
;
static
const
char
*
_jsonPlannedHomePositionKey
;
static
const
char
*
_jsonParamsKey
;
...
...
src/MissionManager/PlanElementController.cc
View file @
e3566933
...
...
@@ -54,4 +54,6 @@ void PlanElementController::_activeVehicleChanged(Vehicle* activeVehicle)
// Whenever vehicle changes we need to update syncInProgress
emit
syncInProgressChanged
(
syncInProgress
());
emit
vehicleChanged
(
_activeVehicle
);
}
src/MissionManager/PlanElementController.h
View file @
e3566933
...
...
@@ -35,6 +35,8 @@ public:
Q_PROPERTY
(
QString
fileExtension
READ
fileExtension
CONSTANT
)
virtual
QString
fileExtension
(
void
)
const
=
0
;
Q_PROPERTY
(
Vehicle
*
vehicle
READ
vehicle
NOTIFY
vehicleChanged
)
/// Should be called immediately upon Component.onCompleted.
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view
Q_INVOKABLE
virtual
void
start
(
bool
editMode
);
...
...
@@ -55,9 +57,12 @@ public:
virtual
bool
dirty
(
void
)
const
=
0
;
virtual
void
setDirty
(
bool
dirty
)
=
0
;
Vehicle
*
vehicle
(
void
)
{
return
_activeVehicle
;
}
signals:
void
syncInProgressChanged
(
bool
syncInProgress
);
void
dirtyChanged
(
bool
dirty
);
void
vehicleChanged
(
Vehicle
*
vehicle
);
protected:
MultiVehicleManager
*
_multiVehicleMgr
;
...
...
src/MissionManager/SurveyMissionItem.cc
View file @
e3566933
...
...
@@ -12,6 +12,7 @@
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h"
#include <QPolygonF>
...
...
@@ -70,6 +71,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
,
_surveyDistance
(
0.0
)
,
_cameraShots
(
0
)
,
_coveredArea
(
0.0
)
,
_timeBetweenShots
(
0.0
)
,
_gridAltitudeFact
(
0
,
_gridAltitudeFactName
,
FactMetaData
::
valueTypeDouble
)
,
_gridAngleFact
(
0
,
_gridAngleFactName
,
FactMetaData
::
valueTypeDouble
)
,
_gridSpacingFact
(
0
,
_gridSpacingFactName
,
FactMetaData
::
valueTypeDouble
)
...
...
@@ -132,7 +134,11 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect
(
&
_cameraResolutionHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_cameraValueChanged
);
connect
(
&
_cameraFocalLengthFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_cameraValueChanged
);
connect
(
this
,
&
SurveyMissionItem
::
cameraTriggerChanged
,
this
,
&
SurveyMissionItem
::
_cameraTriggerChanged
);
connect
(
this
,
&
SurveyMissionItem
::
cameraTriggerChanged
,
this
,
&
SurveyMissionItem
::
_cameraTriggerChanged
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
timeBetweenShotsChanged
);
connect
(
_vehicle
,
&
Vehicle
::
cruiseSpeedChanged
,
this
,
&
SurveyMissionItem
::
timeBetweenShotsChanged
);
connect
(
_vehicle
,
&
Vehicle
::
hoverSpeedChanged
,
this
,
&
SurveyMissionItem
::
timeBetweenShotsChanged
);
}
void
SurveyMissionItem
::
_setSurveyDistance
(
double
surveyDistance
)
...
...
@@ -780,6 +786,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const
pMissionItems
->
append
(
item
);
if
(
_cameraTrigger
&&
i
==
0
)
{
// Turn on camera
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
// sequence number
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
// MAV_CMD
MAV_FRAME_MISSION
,
// MAV_FRAME
...
...
@@ -793,6 +800,7 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const
}
if
(
_cameraTrigger
)
{
// Turn off camera
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
// sequence number
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
// MAV_CMD
MAV_FRAME_MISSION
,
// MAV_FRAME
...
...
@@ -810,10 +818,9 @@ QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const
void
SurveyMissionItem
::
_cameraTriggerChanged
(
void
)
{
setDirty
(
true
);
if
(
_gridPoints
.
count
())
{
// If we have grid turn on/off camera trigger will add/remove two camera trigger mission items
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
}
// Camera trigger adds items
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
// We now have camera shot count
emit
cameraShotsChanged
(
cameraShots
());
}
...
...
@@ -826,3 +833,16 @@ void SurveyMissionItem::_cameraValueChanged(void)
{
emit
cameraValueChanged
();
}
double
SurveyMissionItem
::
timeBetweenShots
(
void
)
const
{
return
_cruiseSpeed
==
0
?
0
:
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
()
/
_cruiseSpeed
;
}
void
SurveyMissionItem
::
setCruiseSpeed
(
double
cruiseSpeed
)
{
if
(
!
qFuzzyCompare
(
_cruiseSpeed
,
cruiseSpeed
))
{
_cruiseSpeed
=
cruiseSpeed
;
emit
timeBetweenShotsChanged
();
}
}
src/MissionManager/SurveyMissionItem.h
View file @
e3566933
...
...
@@ -48,6 +48,7 @@ public:
Q_PROPERTY
(
bool
cameraOrientationLandscape
MEMBER
_cameraOrientationLandscape
NOTIFY
cameraOrientationLandscapeChanged
)
Q_PROPERTY
(
bool
manualGrid
MEMBER
_manualGrid
NOTIFY
manualGridChanged
)
Q_PROPERTY
(
QString
camera
MEMBER
_camera
NOTIFY
cameraChanged
)
Q_PROPERTY
(
double
timeBetweenShots
READ
timeBetweenShots
NOTIFY
timeBetweenShotsChanged
)
Q_INVOKABLE
void
clearPolygon
(
void
);
Q_INVOKABLE
void
addPolygonCoordinate
(
const
QGeoCoordinate
coordinate
);
...
...
@@ -72,6 +73,7 @@ public:
int
cameraShots
(
void
)
const
;
double
coveredArea
(
void
)
const
{
return
_coveredArea
;
}
double
timeBetweenShots
(
void
)
const
;
// Overrides from ComplexMissionItem
...
...
@@ -80,6 +82,8 @@ public:
QmlObjectListModel
*
getMissionItems
(
void
)
const
final
;