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
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
...
...
@@ -33,6 +33,9 @@ const char* MissionController::_jsonFileTypeValue = "Mission";
const
char
*
MissionController
::
_jsonItemsKey
=
"items"
;
const
char
*
MissionController
::
_jsonPlannedHomePositionKey
=
"plannedHomePosition"
;
const
char
*
MissionController
::
_jsonFirmwareTypeKey
=
"firmwareType"
;
const
char
*
MissionController
::
_jsonVehicleTypeKey
=
"vehicleType"
;
const
char
*
MissionController
::
_jsonCruiseSpeedKey
=
"cruiseSpeed"
;
const
char
*
MissionController
::
_jsonHoverSpeedKey
=
"hoverSpeed"
;
const
char
*
MissionController
::
_jsonParamsKey
=
"params"
;
// Deprecated V1 format keys
...
...
@@ -49,9 +52,12 @@ MissionController::MissionController(QObject *parent)
,
_missionItemsRequested
(
false
)
,
_queuedSend
(
false
)
,
_missionDistance
(
0.0
)
,
_missionTime
(
0.0
)
,
_missionHoverDistance
(
0.0
)
,
_missionHoverTime
(
0.0
)
,
_missionCruiseDistance
(
0.0
)
,
_missionCruiseTime
(
0.0
)
,
_missionMaxTelemetry
(
0.0
)
,
_cruiseDistance
(
0.0
)
,
_hoverDistance
(
0.0
)
{
}
...
...
@@ -396,6 +402,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
{
_jsonPlannedHomePositionKey
,
QJsonValue
::
Array
,
true
},
{
_jsonItemsKey
,
QJsonValue
::
Array
,
true
},
{
_jsonFirmwareTypeKey
,
QJsonValue
::
Double
,
true
},
{
_jsonVehicleTypeKey
,
QJsonValue
::
Double
,
false
},
{
_jsonCruiseSpeedKey
,
QJsonValue
::
Double
,
false
},
{
_jsonHoverSpeedKey
,
QJsonValue
::
Double
,
false
},
};
if
(
!
JsonHelper
::
validateKeys
(
json
,
rootKeyInfoList
,
errorString
))
{
return
false
;
...
...
@@ -403,11 +412,21 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
qCDebug
(
MissionControllerLog
)
<<
"MissionController::_loadJsonMissionFileV2 itemCount:"
<<
json
[
_jsonItemsKey
].
toArray
().
count
();
//
Planned home position
//
Mission Settings
QGeoCoordinate
homeCoordinate
;
if
(
!
JsonHelper
::
loadGeoCoordinate
(
json
[
_jsonPlannedHomePositionKey
],
true
/* altitudeRequired */
,
homeCoordinate
,
errorString
))
{
return
false
;
}
if
(
json
.
contains
(
_jsonVehicleTypeKey
)
&&
_activeVehicle
->
isOfflineEditingVehicle
())
{
QGroundControlQmlGlobal
::
offlineEditingVehicleType
()
->
setRawValue
(
json
[
_jsonVehicleTypeKey
].
toDouble
());
}
if
(
json
.
contains
(
_jsonCruiseSpeedKey
))
{
QGroundControlQmlGlobal
::
offlineEditingCruiseSpeed
()
->
setRawValue
(
json
[
_jsonCruiseSpeedKey
].
toDouble
());
}
if
(
json
.
contains
(
_jsonHoverSpeedKey
))
{
QGroundControlQmlGlobal
::
offlineEditingHoverSpeed
()
->
setRawValue
(
json
[
_jsonHoverSpeedKey
].
toDouble
());
}
SimpleMissionItem
*
homeItem
=
new
SimpleMissionItem
(
_activeVehicle
,
this
);
homeItem
->
setCoordinate
(
homeCoordinate
);
visualItems
->
insert
(
0
,
homeItem
);
...
...
@@ -645,19 +664,8 @@ void MissionController::saveToFile(const QString& filename)
missionFileObject
[
JsonHelper
::
jsonVersionKey
]
=
_missionFileVersion
;
missionFileObject
[
JsonHelper
::
jsonGroundStationKey
]
=
JsonHelper
::
jsonGroundStationValue
;
MAV_AUTOPILOT
firmwareType
=
MAV_AUTOPILOT_GENERIC
;
if
(
_activeVehicle
)
{
firmwareType
=
_activeVehicle
->
firmwareType
();
}
else
{
// FIXME: Hack duplicated code from QGroundControlQmlGlobal. Had to do this for now since
// QGroundControlQmlGlobal is not available from C++ side.
QSettings
settings
;
firmwareType
=
(
MAV_AUTOPILOT
)
settings
.
value
(
"OfflineEditingFirmwareType"
,
MAV_AUTOPILOT_ARDUPILOTMEGA
).
toInt
();
}
missionFileObject
[
_jsonFirmwareTypeKey
]
=
firmwareType
;
// Mission settings
// Save planned home position
SimpleMissionItem
*
homeItem
=
qobject_cast
<
SimpleMissionItem
*>
(
_visualItems
->
get
(
0
));
if
(
!
homeItem
)
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Internal error: VisualMissionItem at index 0 not SimpleMissionItem"
));
...
...
@@ -666,6 +674,10 @@ void MissionController::saveToFile(const QString& filename)
QJsonValue
coordinateValue
;
JsonHelper
::
saveGeoCoordinate
(
homeItem
->
coordinate
(),
true
/* writeAltitude */
,
coordinateValue
);
missionFileObject
[
_jsonPlannedHomePositionKey
]
=
coordinateValue
;
missionFileObject
[
_jsonFirmwareTypeKey
]
=
_activeVehicle
->
firmwareType
();
missionFileObject
[
_jsonVehicleTypeKey
]
=
_activeVehicle
->
vehicleType
();
missionFileObject
[
_jsonCruiseSpeedKey
]
=
_activeVehicle
->
cruiseSpeed
();
missionFileObject
[
_jsonHoverSpeedKey
]
=
_activeVehicle
->
hoverSpeed
();
// Save the visual items
QJsonArray
rgMissionItems
;
...
...
@@ -730,7 +742,7 @@ void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionIte
}
}
void
MissionController
::
_calcHomeDist
(
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
homeItem
,
double
*
distance
)
double
MissionController
::
_calcDistanceToHome
(
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
homeItem
)
{
QGeoCoordinate
currentCoord
=
currentItem
->
coordinate
();
QGeoCoordinate
homeCoord
=
homeItem
->
exitCoordinate
();
...
...
@@ -740,11 +752,7 @@ void MissionController::_calcHomeDist(VisualMissionItem* currentItem, VisualMiss
qCDebug
(
MissionControllerLog
)
<<
"distanceOk"
<<
distanceOk
;
if
(
distanceOk
)
{
*
distance
=
homeCoord
.
distanceTo
(
currentCoord
);
}
else
{
*
distance
=
0.0
;
}
return
distanceOk
?
homeCoord
.
distanceTo
(
currentCoord
)
:
0.0
;
}
void
MissionController
::
_recalcWaypointLines
(
void
)
...
...
@@ -771,7 +779,7 @@ void MissionController::_recalcWaypointLines(void)
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
// If we still haven't found the first coordinate item and we hit a
a takeoff command
link back to home
// If we still haven't found the first coordinate item and we hit a
takeoff command,
link back to home
if
(
firstCoordinateItem
&&
item
->
isSimpleItem
()
&&
(
qobject_cast
<
SimpleMissionItem
*>
(
item
)
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
||
...
...
@@ -842,7 +850,7 @@ void MissionController::_recalcAltitudeRangeBearing()
qWarning
()
<<
"Home item is not SimpleMissionItem"
;
}
bool
showHomePosition
=
homeItem
->
showHomePosition
();
bool
showHomePosition
=
homeItem
->
showHomePosition
();
qCDebug
(
MissionControllerLog
)
<<
"_recalcAltitudeRangeBearing"
;
...
...
@@ -862,47 +870,68 @@ void MissionController::_recalcAltitudeRangeBearing()
double
missionDistance
=
0.0
;
double
missionMaxTelemetry
=
0.0
;
double
missionTime
=
0.0
;
double
vtolHoverTime
=
0.0
;
double
vtolCruiseTime
=
0.0
;
double
vtolHoverDistance
=
0.0
;
double
vtolCruiseDistance
=
0.0
;
double
currentCruiseSpeed
=
_activeVehicle
->
cruiseSpeed
();
double
currentHoverSpeed
=
_activeVehicle
->
hoverSpeed
();
bool
vtolCalc
=
(
QGroundControlQmlGlobal
::
offlineEditingVehicleType
()
->
enumStringValue
()
==
"VTOL"
||
(
_activeVehicle
&&
_activeVehicle
->
vtol
()))
?
true
:
false
;
double
cruiseDistance
=
0.0
;
double
hoverDistance
=
0.0
;
bool
hoverDistanceCalc
=
false
;
bool
hoverTransition
=
false
;
bool
cruiseTransition
=
false
;
bool
hoverDistanceReset
=
false
;
bool
vtolVehicle
=
_activeVehicle
->
vtol
();
bool
vtolInHover
=
true
;
bool
linkBackToHome
=
false
;
for
(
int
i
=
1
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
item
);
ComplexMissionItem
*
complexItem
=
qobject_cast
<
ComplexMissionItem
*>
(
item
);
// Assume the worst
item
->
setAzimuth
(
0.0
);
item
->
setDistance
(
0.0
);
// If we still haven't found the first coordinate item and we hit a takeoff command link back to home
if
(
firstCoordinateItem
&&
item
->
isSimpleItem
()
&&
qobject_cast
<
SimpleMissionItem
*>
(
item
)
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
)
{
linkBackToHome
=
true
;
hoverDistanceCalc
=
true
;
if
(
simpleItem
&&
simpleItem
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_DO_CHANGE_SPEED
)
{
// Adjust cruise speed for time calculations
double
newSpeed
=
simpleItem
->
missionItem
().
param2
();
if
(
newSpeed
>
0
)
{
if
(
_activeVehicle
->
multiRotor
())
{
currentHoverSpeed
=
newSpeed
;
}
else
{
currentCruiseSpeed
=
newSpeed
;
}
}
}
if
(
item
->
isSimpleItem
()
&&
vtolCalc
)
{
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
item
);
if
(
simpleItem
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_DO_VTOL_TRANSITION
){
//transition waypoint value
if
(
simpleItem
->
missionItem
().
param1
()
==
3
){
//hover mode value
hoverDistanceCalc
=
true
;
hoverTransition
=
true
;
}
else
if
(
simpleItem
->
missionItem
().
param1
()
==
4
){
hoverDistanceCalc
=
false
;
cruiseTransition
=
true
;
// Link back to home if first item is takeoff and we have home position
if
(
firstCoordinateItem
&&
simpleItem
&&
simpleItem
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
)
{
if
(
showHomePosition
)
{
linkBackToHome
=
true
;
}
}
// Update VTOL state
if
(
simpleItem
&&
vtolVehicle
)
{
switch
(
simpleItem
->
command
())
{
case
MavlinkQmlSingleton
:
:
MAV_CMD_NAV_TAKEOFF
:
vtolInHover
=
false
;
break
;
case
MavlinkQmlSingleton
:
:
MAV_CMD_NAV_LAND
:
vtolInHover
=
false
;
break
;
case
MavlinkQmlSingleton
:
:
MAV_CMD_DO_VTOL_TRANSITION
:
{
int
transitionState
=
simpleItem
->
missionItem
().
param1
();
if
(
transitionState
==
MAV_VTOL_STATE_TRANSITION_TO_MC
)
{
vtolInHover
=
true
;
}
else
if
(
transitionState
==
MAV_VTOL_STATE_TRANSITION_TO_FW
)
{
vtolInHover
=
false
;
}
}
if
(
!
hoverTransition
&&
cruiseTransition
&&
!
hoverDistanceReset
&&
!
linkBackToHome
){
hoverDistance
=
missionDistance
;
hoverDistanceReset
=
true
;
break
;
default:
break
;
}
}
...
...
@@ -927,62 +956,60 @@ void MissionController::_recalcAltitudeRangeBearing()
if
(
!
item
->
isStandaloneCoordinate
())
{
firstCoordinateItem
=
false
;
if
(
lastCoordinateItem
!=
homeItem
||
(
showHomePosition
&&
linkBackToHome
))
{
double
azimuth
,
distance
,
altDifference
,
telemetryDistance
;
if
(
lastCoordinateItem
!=
homeItem
||
linkBackToHome
)
{
// This is a subsequent waypoint or we are forcing the first waypoint back to home
double
azimuth
,
distance
,
altDifference
;
// Subsequent coordinate items link to last coordinate item. If the last coordinate item
// is an invalid home position we skip the line
_calcPrevWaypointValues
(
homePositionAltitude
,
item
,
lastCoordinateItem
,
&
azimuth
,
&
distance
,
&
altDifference
);
item
->
setAltDifference
(
altDifference
);
item
->
setAzimuth
(
azimuth
);
item
->
setDistance
(
distance
);
missionDistance
+=
distance
;
if
(
item
->
isSimpleItem
())
{
_calcHomeDist
(
item
,
homeItem
,
&
telemetryDistance
);
if
(
vtol
Calc
)
{
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
item
);
if
(
simpleItem
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
||
hoverDistanceCalc
){
hoverDistance
+=
distanc
e
;
}
cruiseDistance
=
missionDistance
-
hoverDistance
;
if
(
simpleItem
->
command
()
==
MavlinkQmlSingleton
::
MAV_CMD_NAV_LAND
&&
!
linkBackToHome
&&
!
cruiseTransition
&&
!
hoverTransition
){
hoverDistance
=
cruiseDistanc
e
;
cruiseDistance
=
missionDistance
-
hoverDistanc
e
;
}
missionMaxTelemetry
=
qMax
(
missionMaxTelemetry
,
_calcDistanceToHome
(
item
,
homeItem
));
// Calculate mission time
if
(
vtolVehicle
)
{
if
(
vtol
InHover
)
{
double
hoverTime
=
distance
/
_activeVehicle
->
hoverSpeed
(
);
missionTime
+=
hoverTime
;
vtolHoverTime
+=
hoverTim
e
;
vtolHoverDistance
+=
distance
;
}
else
{
double
cruiseTime
=
distance
/
currentCruiseSpeed
;
missionTime
+=
cruiseTim
e
;
vtolCruiseTime
+=
cruiseTim
e
;
vtolCruiseDistance
+=
distance
;
}
}
else
{
missionDistance
+=
qobject_cast
<
ComplexMissionItem
*>
(
item
)
->
complexDistance
();
telemetryDistance
=
qobject_cast
<
ComplexMissionItem
*>
(
item
)
->
greatestDistanceTo
(
homeItem
->
exitCoordinate
());
if
(
vtolCalc
){
cruiseDistance
+=
qobject_cast
<
ComplexMissionItem
*>
(
item
)
->
complexDistance
();
//assume all survey missions undertaken in cruise
}
}
if
(
telemetryDistance
>
missionMaxTelemetry
)
{
missionMaxTelemetry
=
telemetryDistance
;
missionTime
+=
distance
/
(
_activeVehicle
->
multiRotor
()
?
currentHoverSpeed
:
currentCruiseSpeed
);
}
}
else
if
(
lastCoordinateItem
==
homeItem
&&
!
item
->
isSimpleItem
()){
missionDistance
+=
qobject_cast
<
ComplexMissionItem
*>
(
item
)
->
complexDistance
();
missionMaxTelemetry
=
qobject_cast
<
ComplexMissionItem
*>
(
item
)
->
greatestDistanceTo
(
homeItem
->
exitCoordinate
());
if
(
vtolCalc
){
cruiseDistance
+=
qobject_cast
<
ComplexMissionItem
*>
(
item
)
->
complexDistance
();
//assume all survey missions undertaken in cruise
}
if
(
complexItem
)
{
// Add in distance/time inside survey as well
// This code assumes all surveys are done cruise not hover
double
complexDistance
=
complexItem
->
complexDistance
();
double
cruiseSpeed
=
_activeVehicle
->
multiRotor
()
?
currentHoverSpeed
:
currentCruiseSpeed
;
missionDistance
+=
complexDistance
;
missionTime
+=
complexDistance
/
cruiseSpeed
;
missionMaxTelemetry
=
qMax
(
missionMaxTelemetry
,
complexItem
->
greatestDistanceTo
(
homeItem
->
exitCoordinate
()));
// Let the complex item know the current cruise speed
complexItem
->
setCruiseSpeed
(
cruiseSpeed
);
}
lastCoordinateItem
=
item
;
}
lastCoordinateItem
=
item
;
}
}
setMissionDistance
(
missionDistance
);
setMissionMaxTelemetry
(
missionMaxTelemetry
);
setCruiseDistance
(
cruiseDistance
);
setHoverDistance
(
hoverDistance
);
_setMissionMaxTelemetry
(
missionMaxTelemetry
);
_setMissionDistance
(
missionDistance
);
_setMissionTime
(
missionTime
);
_setMissionHoverDistance
(
vtolHoverDistance
);
_setMissionHoverTime
(
vtolHoverTime
);
_setMissionCruiseDistance
(
vtolCruiseDistance
);
_setMissionCruiseTime
(
vtolCruiseTime
);
// Walk the list again calculating altitude percentages
double
altRange
=
maxAltSeen
-
minAltSeen
;
...
...
@@ -1187,6 +1214,8 @@ void MissionController::_activeVehicleSet(void)
connect
(
missionManager
,
&
MissionManager
::
currentItemChanged
,
this
,
&
MissionController
::
_currentMissionItemChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionAvailableChanged
,
this
,
&
MissionController
::
_activeVehicleHomePositionAvailableChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionController
::
_activeVehicleHomePositionChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
cruiseSpeedChanged
,
this
,
&
MissionController
::
_recalcAltitudeRangeBearing
);
connect
(
_activeVehicle
,
&
Vehicle
::
hoverSpeedChanged
,
this
,
&
MissionController
::
_recalcAltitudeRangeBearing
);
if
(
_activeVehicle
->
parameterManager
()
->
parametersReady
()
&&
!
syncInProgress
())
{
// We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle.
...
...
@@ -1230,7 +1259,15 @@ void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate&
}
}
void
MissionController
::
setMissionDistance
(
double
missionDistance
)
void
MissionController
::
_setMissionMaxTelemetry
(
double
missionMaxTelemetry
)
{
if
(
!
qFuzzyCompare
(
_missionMaxTelemetry
,
missionMaxTelemetry
))
{
_missionMaxTelemetry
=
missionMaxTelemetry
;
emit
missionMaxTelemetryChanged
(
_missionMaxTelemetry
);
}
}
void
MissionController
::
_setMissionDistance
(
double
missionDistance
)
{
if
(
!
qFuzzyCompare
(
_missionDistance
,
missionDistance
))
{
_missionDistance
=
missionDistance
;
...
...
@@ -1238,27 +1275,43 @@ void MissionController::setMissionDistance(double missionDistance)
}
}
void
MissionController
::
setMissionMaxTelemetry
(
double
missionMaxTelemetry
)
void
MissionController
::
_setMissionTime
(
double
missionTime
)
{
if
(
!
qFuzzyCompare
(
_missionMaxTelemetry
,
missionMaxTelemetry
))
{
_missionMaxTelemetry
=
missionMaxTelemetry
;
emit
missionMaxTelemetryChanged
(
_missionMaxTelemetry
);
if
(
!
qFuzzyCompare
(
_missionTime
,
missionTime
))
{
_missionTime
=
missionTime
;
emit
missionTimeChanged
();
}
}
void
MissionController
::
_setMissionHoverTime
(
double
missionHoverTime
)
{
if
(
!
qFuzzyCompare
(
_missionHoverTime
,
missionHoverTime
))
{
_missionHoverTime
=
missionHoverTime
;
emit
missionHoverTimeChanged
();
}
}
void
MissionController
::
setCruiseDistance
(
double
cruise
Distance
)
void
MissionController
::
_setMissionHoverDistance
(
double
missionHover
Distance
)
{
if
(
!
qFuzzyCompare
(
_
cruiseDistance
,
cruise
Distance
))
{
_
cruiseDistance
=
cruise
Distance
;
emit
cruiseDistanceChanged
(
_cruise
Distance
);
if
(
!
qFuzzyCompare
(
_
missionHoverDistance
,
missionHover
Distance
))
{
_
missionHoverDistance
=
missionHover
Distance
;
emit
missionHoverDistanceChanged
(
_missionHover
Distance
);
}
}
void
MissionController
::
setHoverDistance
(
double
hoverDistanc
e
)
void
MissionController
::
_setMissionCruiseTime
(
double
missionCruiseTim
e
)
{
if
(
!
qFuzzyCompare
(
_hoverDistance
,
hoverDistance
))
{
_hoverDistance
=
hoverDistance
;
emit
hoverDistanceChanged
(
_hoverDistance
);
if
(
!
qFuzzyCompare
(
_missionCruiseTime
,
missionCruiseTime
))
{
_missionCruiseTime
=
missionCruiseTime
;
emit
missionCruiseTimeChanged
();
}
}
void
MissionController
::
_setMissionCruiseDistance
(
double
missionCruiseDistance
)
{
if
(
!
qFuzzyCompare
(
_missionCruiseDistance
,
missionCruiseDistance
))
{
_missionCruiseDistance
=
missionCruiseDistance
;
emit
missionCruiseDistanceChanged
(
_missionCruiseDistance
);
}
}
...
...
@@ -1437,3 +1490,21 @@ QString MissionController::fileExtension(void) const
{
return
QGCApplication
::
missionFileExtension
;
}
double
MissionController
::
cruiseSpeed
(
void
)
const
{
if
(
_activeVehicle
)
{
return
_activeVehicle
->
cruiseSpeed
();
}
else
{
return
0.0
f
;
}
}
double
MissionController
::
hoverSpeed
(
void
)
const
{
if
(
_activeVehicle
)
{
return
_activeVehicle
->
hoverSpeed
();
}
else
{
return
0.0
f
;
}
}
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
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
double
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
final
;
void
setCruiseSpeed
(
double
cruiseSpeed
)
final
;
// Overrides from VisualMissionItem
...
...
@@ -121,6 +125,7 @@ signals:
void
cameraOrientationLandscapeChanged
(
bool
cameraOrientationLandscape
);
void
cameraChanged
(
QString
camera
);
void
manualGridChanged
(
bool
manualGrid
);
void
timeBetweenShotsChanged
(
void
);
private
slots
:
void
_cameraTriggerChanged
(
void
);
...
...
@@ -158,6 +163,8 @@ private:
double
_surveyDistance
;
int
_cameraShots
;
double
_coveredArea
;
double
_timeBetweenShots
;
double
_cruiseSpeed
;
Fact
_gridAltitudeFact
;
Fact
_gridAngleFact
;
...
...
@@ -198,7 +205,6 @@ private:
static
const
char
*
_jsonCameraOrientationLandscapeKey
;
static
const
char
*
_jsonFixedValueIsAltitudeKey
;
static
const
char
*
_gridAltitudeFactName
;
static
const
char
*
_gridAngleFactName
;
static
const
char
*
_gridSpacingFactName
;
...
...
src/QmlControls/QGroundControlQmlGlobal.json
View file @
e3566933
...
...
@@ -3,7 +3,7 @@
"name"
:
"OfflineEditingFirmwareType"
,
"shortDescription"
:
"Offline editing firmware type"
,
"type"
:
"uint32"
,
"enumStrings"
:
"ArduPilot
Firmware,PX4 Pro Firmware,Mavlink Generic Firmware
"
,
"enumStrings"
:
"ArduPilot
,PX4 Pro,Mavlink Generic
"
,
"enumValues"
:
"3,12,0"
,
"defaultValue"
:
3
},
...
...
@@ -11,7 +11,7 @@
"name"
:
"OfflineEditingVehicleType"
,
"shortDescription"
:
"Offline editing vehicle type"
,
"type"
:
"uint32"
,
"enumStrings"
:
"Fixed
wing,Multicopte
r,VTOL,Rover,Sub"
,
"enumStrings"
:
"Fixed
Wing,Multi-Roto
r,VTOL,Rover,Sub"
,
"enumValues"
:
"1,2,19,10,12"
,
"defaultValue"
:
1
},
...
...
src/Vehicle/Vehicle.cc
View file @
e3566933
...
...
@@ -96,6 +96,8 @@ Vehicle::Vehicle(LinkInterface* link,
,
_onboardControlSensorsUnhealthy
(
0
)
,
_gpsRawIntMessageAvailable
(
false
)
,
_globalPositionIntMessageAvailable
(
false
)
,
_cruiseSpeed
(
QGroundControlQmlGlobal
::
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_hoverSpeed
(
QGroundControlQmlGlobal
::
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_connectionLost
(
false
)
,
_connectionLostEnabled
(
true
)
,
_missionManager
(
NULL
)
...
...
@@ -150,7 +152,7 @@ Vehicle::Vehicle(LinkInterface* link,
connect
(
_uas
,
&
UAS
::
imageReady
,
this
,
&
Vehicle
::
_imageReady
);
connect
(
this
,
&
Vehicle
::
remoteControlRSSIChanged
,
this
,
&
Vehicle
::
_remoteControlRSSIChanged
);
_
firmwarePlugin
=
_firmwarePluginManager
->
firmwarePluginForAutopilot
(
_firmwareType
,
_vehicleType
);
_
commonInit
(
);
_autopilotPlugin
=
_firmwarePlugin
->
autopilotPlugin
(
this
);
// connect this vehicle to the follow me handle manager
...
...
@@ -183,21 +185,6 @@ Vehicle::Vehicle(LinkInterface* link,
_loadSettings
();
_missionManager
=
new
MissionManager
(
this
);
connect
(
_missionManager
,
&
MissionManager
::
error
,
this
,
&
Vehicle
::
_missionManagerError
);
connect
(
_missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
Vehicle
::
_newMissionItemsAvailable
);
_parameterManager
=
new
ParameterManager
(
this
);
connect
(
_parameterManager
,
&
ParameterManager
::
parametersReadyChanged
,
this
,
&
Vehicle
::
_parametersReady
);
// GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager
=
_firmwarePlugin
->
newGeoFenceManager
(
this
);
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
error
,
this
,
&
Vehicle
::
_geoFenceManagerError
);
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
loadComplete
,
this
,
&
Vehicle
::
_newGeoFenceAvailable
);
_rallyPointManager
=
_firmwarePlugin
->
newRallyPointManager
(
this
);
connect
(
_rallyPointManager
,
&
RallyPointManager
::
error
,
this
,
&
Vehicle
::
_rallyPointManagerError
);
// Ask the vehicle for firmware version info.
sendMavCommand
(
MAV_COMP_ID_ALL
,
// Don't know default component id yet.
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES
,
...
...
@@ -214,27 +201,6 @@ Vehicle::Vehicle(LinkInterface* link,
// Invalidate the timer to signal first announce
_lowBatteryAnnounceTimer
.
invalidate
();
// Build FactGroup object model
_addFact
(
&
_rollFact
,
_rollFactName
);
_addFact
(
&
_pitchFact
,
_pitchFactName
);
_addFact
(
&
_headingFact
,
_headingFactName
);
_addFact
(
&
_groundSpeedFact
,
_groundSpeedFactName
);
_addFact
(
&
_airSpeedFact
,
_airSpeedFactName
);
_addFact
(
&
_climbRateFact
,
_climbRateFactName
);
_addFact
(
&
_altitudeRelativeFact
,
_altitudeRelativeFactName
);
_addFact
(
&
_altitudeAMSLFact
,
_altitudeAMSLFactName
);
_addFactGroup
(
&
_gpsFactGroup
,
_gpsFactGroupName
);
_addFactGroup
(
&
_batteryFactGroup
,
_batteryFactGroupName
);
_addFactGroup
(
&
_windFactGroup
,
_windFactGroupName
);
_addFactGroup
(
&
_vibrationFactGroup
,
_vibrationFactGroupName
);
_gpsFactGroup
.
setVehicle
(
this
);
_batteryFactGroup
.
setVehicle
(
this
);
_windFactGroup
.
setVehicle
(
this
);
_vibrationFactGroup
.
setVehicle
(
this
);
}
// Disconnected Vehicle for offline editing
...
...
@@ -275,6 +241,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_onboardControlSensorsUnhealthy
(
0
)
,
_gpsRawIntMessageAvailable
(
false
)
,
_globalPositionIntMessageAvailable
(
false
)
,
_cruiseSpeed
(
QGroundControlQmlGlobal
::
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_hoverSpeed
(
QGroundControlQmlGlobal
::
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_connectionLost
(
false
)
,
_connectionLostEnabled
(
true
)
,
_missionManager
(
NULL
)
...
...
@@ -314,8 +282,13 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_windFactGroup
(
this
)
,
_vibrationFactGroup
(
this
)
{
_
firmwarePlugin
=
_firmwarePluginManager
->
firmwarePluginForAutopilot
(
_firmwareType
,
_vehicleType
);
_
commonInit
(
);
_firmwarePlugin
->
initializeVehicle
(
this
);
}
void
Vehicle
::
_commonInit
(
void
)
{
_firmwarePlugin
=
_firmwarePluginManager
->
firmwarePluginForAutopilot
(
_firmwareType
,
_vehicleType
);
_missionManager
=
new
MissionManager
(
this
);
connect
(
_missionManager
,
&
MissionManager
::
error
,
this
,
&
Vehicle
::
_missionManagerError
);
...
...
@@ -329,6 +302,12 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_rallyPointManager
=
_firmwarePlugin
->
newRallyPointManager
(
this
);
connect
(
_rallyPointManager
,
&
RallyPointManager
::
error
,
this
,
&
Vehicle
::
_rallyPointManagerError
);
// Offline editing vehicle tracks settings changes for offline editing settings
connect
(
QGroundControlQmlGlobal
::
offlineEditingFirmwareType
(),
&
Fact
::
rawValueChanged
,
this
,
&
Vehicle
::
_offlineFirmwareTypeSettingChanged
);
connect
(
QGroundControlQmlGlobal
::
offlineEditingVehicleType
(),
&
Fact
::
rawValueChanged
,
this
,
&
Vehicle
::
_offlineVehicleTypeSettingChanged
);
connect
(
QGroundControlQmlGlobal
::
offlineEditingCruiseSpeed
(),
&
Fact
::
rawValueChanged
,
this
,
&
Vehicle
::
_offlineCruiseSpeedSettingChanged
);
connect
(
QGroundControlQmlGlobal
::
offlineEditingHoverSpeed
(),
&
Fact
::
rawValueChanged
,
this
,
&
Vehicle
::
_offlineHoverSpeedSettingChanged
);
// Build FactGroup object model
_addFact
(
&
_rollFact
,
_rollFactName
);
...
...
@@ -344,11 +323,6 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_addFactGroup
(
&
_batteryFactGroup
,
_batteryFactGroupName
);
_addFactGroup
(
&
_windFactGroup
,
_windFactGroupName
);
_addFactGroup
(
&
_vibrationFactGroup
,
_vibrationFactGroupName
);
_gpsFactGroup
.
setVehicle
(
NULL
);
_batteryFactGroup
.
setVehicle
(
NULL
);
_windFactGroup
.
setVehicle
(
NULL
);
_vibrationFactGroup
.
setVehicle
(
NULL
);
}
Vehicle
::~
Vehicle
()
...
...
@@ -366,8 +340,59 @@ Vehicle::~Vehicle()
}
void
Vehicle
::
resetCounters
()
void
Vehicle
::
_offlineFirmwareTypeSettingChanged
(
QVariant
value
)
{
_firmwareType
=
static_cast
<
MAV_AUTOPILOT
>
(
value
.
toInt
());
emit
firmwareTypeChanged
();
}
void
Vehicle
::
_offlineVehicleTypeSettingChanged
(
QVariant
value
)
{
_vehicleType
=
static_cast
<
MAV_TYPE
>
(
value
.
toInt
());
emit
vehicleTypeChanged
();
}
void
Vehicle
::
_offlineCruiseSpeedSettingChanged
(
QVariant
value
)
{
_cruiseSpeed
=
value
.
toDouble
();
emit
cruiseSpeedChanged
(
_cruiseSpeed
);
}
void
Vehicle
::
_offlineHoverSpeedSettingChanged
(
QVariant
value
)
{
_hoverSpeed
=
value
.
toDouble
();
emit
hoverSpeedChanged
(
_hoverSpeed
);
}
QString
Vehicle
::
firmwareTypeString
(
void
)
const
{
if
(
px4Firmware
())
{
return
QStringLiteral
(
"PX4 Pro"
);
}
else
if
(
apmFirmware
())
{
return
QStringLiteral
(
"ArduPilot"
);
}
else
{
return
tr
(
"MAVLink Generic"
);
}
}
QString
Vehicle
::
vehicleTypeString
(
void
)
const
{
if
(
fixedWing
())
{
return
tr
(
"Fixed Wing"
);
}
else
if
(
multiRotor
())
{
return
tr
(
"Multi-Rotor"
);
}
else
if
(
vtol
())
{
return
tr
(
"VTOL"
);
}
else
if
(
rover
())
{
return
tr
(
"Rover"
);
}
else
if
(
sub
())
{
return
tr
(
"Sub"
);
}
else
{
return
tr
(
"Unknown"
);
}
}
void
Vehicle
::
resetCounters
()
{
_messagesReceived
=
0
;
_messagesSent
=
0
;
...
...
@@ -2084,7 +2109,6 @@ const char* VehicleGPSFactGroup::_lockFactName = "lock";
VehicleGPSFactGroup
::
VehicleGPSFactGroup
(
QObject
*
parent
)
:
FactGroup
(
1000
,
":/json/Vehicle/GPSFact.json"
,
parent
)
,
_vehicle
(
NULL
)
,
_hdopFact
(
0
,
_hdopFactName
,
FactMetaData
::
valueTypeDouble
)
,
_vdopFact
(
0
,
_vdopFactName
,
FactMetaData
::
valueTypeDouble
)
,
_courseOverGroundFact
(
0
,
_courseOverGroundFactName
,
FactMetaData
::
valueTypeDouble
)
...
...
@@ -2169,11 +2193,6 @@ QString Vehicle::takeControlFlightMode(void) const
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
VehicleGPSFactGroup
::
setVehicle
(
Vehicle
*
vehicle
)
{
_vehicle
=
vehicle
;
}
const
char
*
VehicleBatteryFactGroup
::
_voltageFactName
=
"voltage"
;
const
char
*
VehicleBatteryFactGroup
::
_percentRemainingFactName
=
"percentRemaining"
;
const
char
*
VehicleBatteryFactGroup
::
_mahConsumedFactName
=
"mahConsumed"
;
...
...
@@ -2192,7 +2211,6 @@ const int VehicleBatteryFactGroup::_cellCountUnavailable = -1.0;
VehicleBatteryFactGroup
::
VehicleBatteryFactGroup
(
QObject
*
parent
)
:
FactGroup
(
1000
,
":/json/Vehicle/BatteryFact.json"
,
parent
)
,
_vehicle
(
NULL
)
,
_voltageFact
(
0
,
_voltageFactName
,
FactMetaData
::
valueTypeDouble
)
,
_percentRemainingFact
(
0
,
_percentRemainingFactName
,
FactMetaData
::
valueTypeInt32
)
,
_mahConsumedFact
(
0
,
_mahConsumedFactName
,
FactMetaData
::
valueTypeInt32
)
...
...
@@ -2216,18 +2234,12 @@ VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
_cellCountFact
.
setRawValue
(
_cellCountUnavailable
);
}
void
VehicleBatteryFactGroup
::
setVehicle
(
Vehicle
*
vehicle
)
{
_vehicle
=
vehicle
;
}
const
char
*
VehicleWindFactGroup
::
_directionFactName
=
"direction"
;
const
char
*
VehicleWindFactGroup
::
_speedFactName
=
"speed"
;
const
char
*
VehicleWindFactGroup
::
_verticalSpeedFactName
=
"verticalSpeed"
;
VehicleWindFactGroup
::
VehicleWindFactGroup
(
QObject
*
parent
)
:
FactGroup
(
1000
,
":/json/Vehicle/WindFact.json"
,
parent
)
,
_vehicle
(
NULL
)
,
_directionFact
(
0
,
_directionFactName
,
FactMetaData
::
valueTypeDouble
)
,
_speedFact
(
0
,
_speedFactName
,
FactMetaData
::
valueTypeDouble
)
,
_verticalSpeedFact
(
0
,
_verticalSpeedFactName
,
FactMetaData
::
valueTypeDouble
)
...
...
@@ -2242,11 +2254,6 @@ VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
_verticalSpeedFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
}
void
VehicleWindFactGroup
::
setVehicle
(
Vehicle
*
vehicle
)
{
_vehicle
=
vehicle
;
}
const
char
*
VehicleVibrationFactGroup
::
_xAxisFactName
=
"xAxis"
;
const
char
*
VehicleVibrationFactGroup
::
_yAxisFactName
=
"yAxis"
;
const
char
*
VehicleVibrationFactGroup
::
_zAxisFactName
=
"zAxis"
;
...
...
@@ -2256,7 +2263,6 @@ const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3";
VehicleVibrationFactGroup
::
VehicleVibrationFactGroup
(
QObject
*
parent
)
:
FactGroup
(
1000
,
":/json/Vehicle/VibrationFact.json"
,
parent
)
,
_vehicle
(
NULL
)
,
_xAxisFact
(
0
,
_xAxisFactName
,
FactMetaData
::
valueTypeDouble
)
,
_yAxisFact
(
0
,
_yAxisFactName
,
FactMetaData
::
valueTypeDouble
)
,
_zAxisFact
(
0
,
_zAxisFactName
,
FactMetaData
::
valueTypeDouble
)
...
...
@@ -2276,8 +2282,3 @@ VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
_yAxisFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_zAxisFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
}
void
VehicleVibrationFactGroup
::
setVehicle
(
Vehicle
*
vehicle
)
{
_vehicle
=
vehicle
;
}
src/Vehicle/Vehicle.h
View file @
e3566933
...
...
@@ -63,8 +63,6 @@ public:
Fact
*
clipCount2
(
void
)
{
return
&
_clipCount2Fact
;
}
Fact
*
clipCount3
(
void
)
{
return
&
_clipCount3Fact
;
}
void
setVehicle
(
Vehicle
*
vehicle
);
static
const
char
*
_xAxisFactName
;
static
const
char
*
_yAxisFactName
;
static
const
char
*
_zAxisFactName
;
...
...
@@ -73,7 +71,6 @@ public:
static
const
char
*
_clipCount3FactName
;
private:
Vehicle
*
_vehicle
;
Fact
_xAxisFact
;
Fact
_yAxisFact
;
Fact
_zAxisFact
;
...
...
@@ -97,14 +94,11 @@ public:
Fact
*
speed
(
void
)
{
return
&
_speedFact
;
}
Fact
*
verticalSpeed
(
void
)
{
return
&
_verticalSpeedFact
;
}
void
setVehicle
(
Vehicle
*
vehicle
);
static
const
char
*
_directionFactName
;
static
const
char
*
_speedFactName
;
static
const
char
*
_verticalSpeedFactName
;
private:
Vehicle
*
_vehicle
;
Fact
_directionFact
;
Fact
_speedFact
;
Fact
_verticalSpeedFact
;
...
...
@@ -129,8 +123,6 @@ public:
Fact
*
count
(
void
)
{
return
&
_countFact
;
}
Fact
*
lock
(
void
)
{
return
&
_lockFact
;
}
void
setVehicle
(
Vehicle
*
vehicle
);
static
const
char
*
_hdopFactName
;
static
const
char
*
_vdopFactName
;
static
const
char
*
_courseOverGroundFactName
;
...
...
@@ -138,7 +130,6 @@ public:
static
const
char
*
_lockFactName
;
private:
Vehicle
*
_vehicle
;
Fact
_hdopFact
;
Fact
_vdopFact
;
Fact
_courseOverGroundFact
;
...
...
@@ -168,8 +159,6 @@ public:
Fact
*
cellCount
(
void
)
{
return
&
_cellCountFact
;
}
void
setVehicle
(
Vehicle
*
vehicle
);
static
const
char
*
_voltageFactName
;
static
const
char
*
_percentRemainingFactName
;
static
const
char
*
_mahConsumedFactName
;
...
...
@@ -187,7 +176,6 @@ public:
static
const
int
_cellCountUnavailable
;
private:
Vehicle
*
_vehicle
;
Fact
_voltageFact
;
Fact
_percentRemainingFact
;
Fact
_mahConsumedFact
;
...
...
@@ -245,8 +233,8 @@ public:
Q_PROPERTY
(
bool
active
READ
active
WRITE
setActive
NOTIFY
activeChanged
)
Q_PROPERTY
(
int
flowImageIndex
READ
flowImageIndex
NOTIFY
flowImageIndexChanged
)
Q_PROPERTY
(
int
rcRSSI
READ
rcRSSI
NOTIFY
rcRSSIChanged
)
Q_PROPERTY
(
bool
px4Firmware
READ
px4Firmware
CONSTANT
)
Q_PROPERTY
(
bool
apmFirmware
READ
apmFirmware
CONSTANT
)
Q_PROPERTY
(
bool
px4Firmware
READ
px4Firmware
NOTIFY
firmwareTypeChanged
)
Q_PROPERTY
(
bool
apmFirmware
READ
apmFirmware
NOTIFY
firmwareTypeChanged
)
Q_PROPERTY
(
bool
soloFirmware
READ
soloFirmware
WRITE
setSoloFirmware
NOTIFY
soloFirmwareChanged
)
Q_PROPERTY
(
bool
genericFirmware
READ
genericFirmware
CONSTANT
)
Q_PROPERTY
(
bool
connectionLost
READ
connectionLost
NOTIFY
connectionLostChanged
)
...
...
@@ -254,26 +242,28 @@ public:
Q_PROPERTY
(
uint
messagesReceived
READ
messagesReceived
NOTIFY
messagesReceivedChanged
)
Q_PROPERTY
(
uint
messagesSent
READ
messagesSent
NOTIFY
messagesSentChanged
)
Q_PROPERTY
(
uint
messagesLost
READ
messagesLost
NOTIFY
messagesLostChanged
)
Q_PROPERTY
(
bool
fixedWing
READ
fixedWing
CONSTANT
)
Q_PROPERTY
(
bool
multiRotor
READ
multiRotor
CONSTANT
)
Q_PROPERTY
(
bool
vtol
READ
vtol
CONSTANT
)
Q_PROPERTY
(
bool
rover
READ
rover
CONSTANT
)
Q_PROPERTY
(
bool
fixedWing
READ
fixedWing
NOTIFY
vehicleTypeChanged
)
Q_PROPERTY
(
bool
multiRotor
READ
multiRotor
NOTIFY
vehicleTypeChanged
)
Q_PROPERTY
(
bool
vtol
READ
vtol
NOTIFY
vehicleTypeChanged
)
Q_PROPERTY
(
bool
rover
READ
rover
NOTIFY
vehicleTypeChanged
)
Q_PROPERTY
(
bool
sub
READ
sub
NOTIFY
vehicleTypeChanged
)
Q_PROPERTY
(
bool
supportsManualControl
READ
supportsManualControl
CONSTANT
)
Q_PROPERTY
(
bool
supportsThrottleModeCenterZero
READ
supportsThrottleModeCenterZero
CONSTANT
)
Q_PROPERTY
(
bool
supportsJSButton
READ
supportsJSButton
CONSTANT
)
Q_PROPERTY
(
bool
supportsRadio
READ
supportsRadio
CONSTANT
)
Q_PROPERTY
(
bool
sub
READ
sub
CONSTANT
)
Q_PROPERTY
(
bool
autoDisconnect
MEMBER
_autoDisconnect
NOTIFY
autoDisconnectChanged
)
Q_PROPERTY
(
QString
prearmError
READ
prearmError
WRITE
setPrearmError
NOTIFY
prearmErrorChanged
)
Q_PROPERTY
(
int
motorCount
READ
motorCount
CONSTANT
)
Q_PROPERTY
(
bool
coaxialMotors
READ
coaxialMotors
CONSTANT
)
Q_PROPERTY
(
bool
xConfigMotors
READ
xConfigMotors
CONSTANT
)
Q_PROPERTY
(
bool
isOfflineEditingVehicle
READ
isOfflineEditingVehicle
CONSTANT
)
Q_PROPERTY
(
QString
brandImage
READ
brandImage
CONSTANT
)
Q_PROPERTY
(
QString
brandImage
READ
brandImage
NOTIFY
firmwareTypeChanged
)
Q_PROPERTY
(
QStringList
unhealthySensors
READ
unhealthySensors
NOTIFY
unhealthySensorsChanged
)
Q_PROPERTY
(
QString
missionFlightMode
READ
missionFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
rtlFlightMode
READ
rtlFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
takeControlFlightMode
READ
takeControlFlightMode
CONSTANT
)
Q_PROPERTY
(
QString
firmwareTypeString
READ
firmwareTypeString
NOTIFY
firmwareTypeChanged
)
Q_PROPERTY
(
QString
vehicleTypeString
READ
vehicleTypeString
NOTIFY
vehicleTypeChanged
)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY
(
bool
flying
READ
flying
WRITE
setFlying
NOTIFY
flyingChanged
)
...
...
@@ -528,6 +518,10 @@ public:
QString
missionFlightMode
()
const
;
QString
rtlFlightMode
()
const
;
QString
takeControlFlightMode
()
const
;
double
cruiseSpeed
()
const
{
return
_cruiseSpeed
;
}
double
hoverSpeed
()
const
{
return
_hoverSpeed
;
}
QString
firmwareTypeString
()
const
;
QString
vehicleTypeString
()
const
;
Fact
*
roll
(
void
)
{
return
&
_rollFact
;
}
Fact
*
heading
(
void
)
{
return
&
_headingFact
;
}
...
...
@@ -615,6 +609,10 @@ signals:
void
prearmErrorChanged
(
const
QString
&
prearmError
);
void
soloFirmwareChanged
(
bool
soloFirmware
);
void
unhealthySensorsChanged
(
void
);
void
cruiseSpeedChanged
(
double
cruiseSpeed
);
void
hoverSpeedChanged
(
double
hoverSpeed
);
void
firmwareTypeChanged
(
void
);
void
vehicleTypeChanged
(
void
);
void
messagesReceivedChanged
();
void
messagesSentChanged
();
...
...
@@ -673,6 +671,10 @@ private slots:
void
_remoteControlRSSIChanged
(
uint8_t
rssi
);
void
_handleFlightModeChanged
(
const
QString
&
flightMode
);
void
_announceArmedChanged
(
bool
armed
);
void
_offlineFirmwareTypeSettingChanged
(
QVariant
value
);
void
_offlineVehicleTypeSettingChanged
(
QVariant
value
);
void
_offlineCruiseSpeedSettingChanged
(
QVariant
value
);
void
_offlineHoverSpeedSettingChanged
(
QVariant
value
);
void
_handleTextMessage
(
int
newCount
);
void
_handletextMessageReceived
(
UASMessage
*
message
);
...
...
@@ -724,8 +726,8 @@ private:
void
_ackMavlinkLogData
(
uint16_t
sequence
);
void
_sendNextQueuedMavCommand
(
void
);
void
_updatePriorityLink
(
void
);
void
_commonInit
(
void
);
private:
int
_id
;
///< Mavlink system id
bool
_active
;
bool
_offlineEditingVehicle
;
///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
...
...
@@ -771,6 +773,8 @@ private:
uint32_t
_onboardControlSensorsUnhealthy
;
bool
_gpsRawIntMessageAvailable
;
bool
_globalPositionIntMessageAvailable
;
double
_cruiseSpeed
;
double
_hoverSpeed
;
typedef
struct
{
int
component
;
...
...
src/ui/preferences/GeneralSettings.qml
View file @
e3566933
...
...
@@ -13,6 +13,7 @@ import QtQuick.Controls 1.2
import
QtQuick
.
Controls
.
Styles
1.2
import
QtQuick
.
Dialogs
1.1
import
QtMultimedia
5.5
import
QtQuick
.
Layouts
1.2
import
QGroundControl
1.0
import
QGroundControl
.
FactSystem
1.0
...
...
@@ -33,6 +34,10 @@ QGCView {
property
Fact
_percentRemainingAnnounce
:
QGroundControl
.
batteryPercentRemainingAnnounce
property
real
_labelWidth
:
ScreenTools
.
defaultFontPixelWidth
*
15
property
real
_editFieldWidth
:
ScreenTools
.
defaultFontPixelWidth
*
30
property
bool
_showCruiseSpeed
:
offlineVehicleCombo
.
currentText
!=
"
Multicopter
"
property
bool
_showHoverSpeed
:
offlineVehicleCombo
.
currentText
!=
"
FixedWing
"
readonly
property
string
_requiresRestart
:
qsTr
(
"
(Requires Restart)
"
)
QGCPalette
{
id
:
qgcPal
}
...
...
@@ -117,90 +122,6 @@ QGCView {
}
}
//-----------------------------------------------------------------
//-- Offline mission editing
Item
{
width
:
qgcView
.
width
*
0.8
height
:
offlineLabel
.
height
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
QGCLabel
{
id
:
offlineLabel
text
:
qsTr
(
"
Offline Mission Editing (Requires Restart)
"
)
font.family
:
ScreenTools
.
demiboldFontFamily
}
}
Rectangle
{
height
:
offlineCol
.
height
+
(
ScreenTools
.
defaultFontPixelHeight
*
2
)
width
:
qgcView
.
width
*
0.8
color
:
qgcPal
.
windowShade
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
Column
{
id
:
offlineCol
spacing
:
ScreenTools
.
defaultFontPixelWidth
anchors.centerIn
:
parent
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
QGCLabel
{
text
:
qsTr
(
"
Firmware:
"
)
width
:
_labelWidth
anchors.baseline
:
offlineTypeCombo
.
baseline
}
FactComboBox
{
id
:
offlineTypeCombo
width
:
_editFieldWidth
fact
:
QGroundControl
.
offlineEditingFirmwareType
indexModel
:
false
}
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
QGCLabel
{
text
:
qsTr
(
"
Vehicle:
"
)
width
:
_labelWidth
anchors.baseline
:
offlineVehicleCombo
.
baseline
}
FactComboBox
{
id
:
offlineVehicleCombo
width
:
_editFieldWidth
fact
:
QGroundControl
.
offlineEditingVehicleType
indexModel
:
false
}
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
offlineVehicleCombo
.
currentText
!=
"
Multicopter
"
QGCLabel
{
text
:
qsTr
(
"
Cruise speed:
"
)
width
:
_labelWidth
anchors.baseline
:
cruiseSpeedField
.
baseline
}
FactTextField
{
id
:
cruiseSpeedField
width
:
_editFieldWidth
fact
:
QGroundControl
.
offlineEditingCruiseSpeed
enabled
:
true
}
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
offlineVehicleCombo
.
currentText
!=
"
Fixedwing
"
QGCLabel
{
id
:
hoverSpeedLabel
text
:
qsTr
(
"
Hover speed:
"
)
width
:
_labelWidth
anchors.baseline
:
hoverSpeedField
.
baseline
}
FactTextField
{
id
:
hoverSpeedField
width
:
_editFieldWidth
fact
:
QGroundControl
.
offlineEditingHoverSpeed
enabled
:
true
}
}
}
}
//-----------------------------------------------------------------
//-- Miscelanous
Item
{
width
:
qgcView
.
width
*
0.8
...
...
@@ -274,7 +195,7 @@ QGCView {
}
QGCLabel
{
anchors.verticalCenter
:
parent
.
verticalCenter
text
:
qsTr
(
"
(Requires Restart)
"
)
text
:
_requiresRestart
}
}
//-----------------------------------------------------------------
...
...
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