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
cff65ebe
Commit
cff65ebe
authored
Mar 25, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Better initial map positions and planned home position support
parent
079ffd7a
Changes
42
Hide whitespace changes
Inline
Side-by-side
Showing
42 changed files
with
291 additions
and
435 deletions
+291
-435
qgroundcontrol.pro
qgroundcontrol.pro
+3
-3
qgroundcontrol.qrc
qgroundcontrol.qrc
+20
-20
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+28
-20
FlightMap.qml
src/FlightMap/FlightMap.qml
+20
-35
CenterMapDropPanel.qml
src/FlightMap/Widgets/CenterMapDropPanel.qml
+2
-16
MissionController.cc
src/MissionManager/MissionController.cc
+83
-123
MissionController.h
src/MissionManager/MissionController.h
+3
-5
MissionSettings.FactMetaData.json
src/MissionManager/MissionSettings.FactMetaData.json
+0
-14
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+60
-68
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+6
-13
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+0
-1
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+0
-3
VisualMissionItem.cc
src/MissionManager/VisualMissionItem.cc
+0
-11
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+0
-5
CameraSection.qml
src/PlanView/CameraSection.qml
+0
-0
FWLandingPatternEditor.qml
src/PlanView/FWLandingPatternEditor.qml
+0
-0
FWLandingPatternMapVisual.qml
src/PlanView/FWLandingPatternMapVisual.qml
+0
-0
GeoFenceEditor.qml
src/PlanView/GeoFenceEditor.qml
+0
-0
GeoFenceMapVisuals.qml
src/PlanView/GeoFenceMapVisuals.qml
+0
-0
MissionItemEditor.qml
src/PlanView/MissionItemEditor.qml
+0
-0
MissionItemMapVisual.qml
src/PlanView/MissionItemMapVisual.qml
+0
-0
MissionItemStatus.qml
src/PlanView/MissionItemStatus.qml
+0
-0
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+4
-18
MissionSettingsMapVisual.qml
src/PlanView/MissionSettingsMapVisual.qml
+1
-1
PlanToolBar.qml
src/PlanView/PlanToolBar.qml
+0
-0
PlanView.qml
src/PlanView/PlanView.qml
+0
-21
QGCMapPolygonControls.qml
src/PlanView/QGCMapPolygonControls.qml
+0
-0
RallyPointEditorHeader.qml
src/PlanView/RallyPointEditorHeader.qml
+0
-0
RallyPointItemEditor.qml
src/PlanView/RallyPointItemEditor.qml
+0
-0
SectionHeader.qml
src/PlanView/SectionHeader.qml
+0
-0
SimpleItemEditor.qml
src/PlanView/SimpleItemEditor.qml
+0
-0
SimpleItemMapVisual.qml
src/PlanView/SimpleItemMapVisual.qml
+0
-0
SurveyItemEditor.qml
src/PlanView/SurveyItemEditor.qml
+0
-0
SurveyMapVisual.qml
src/PlanView/SurveyMapVisual.qml
+0
-0
QGCApplication.cc
src/QGCApplication.cc
+0
-19
QGCApplication.h
src/QGCApplication.h
+0
-8
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+46
-0
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+11
-7
OfflineMap.qml
src/QtLocationPlugin/QMLControl/OfflineMap.qml
+1
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+0
-1
QGCFlightGearLink.cc
src/comm/QGCFlightGearLink.cc
+2
-1
MainWindowInner.qml
src/ui/MainWindowInner.qml
+1
-21
No files found.
qgroundcontrol.pro
View file @
cff65ebe
...
...
@@ -307,7 +307,7 @@ INCLUDEPATH += \
src/FollowMe \
src/GPS \
src/Joystick \
src/
MissionEditor
\
src/
PlanView
\
src/MissionManager \
src/PositionManager \
src/QmlControls \
...
...
@@ -462,7 +462,7 @@ HEADERS += \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
src/MissionManager/MissionSettings
Complex
Item.h \
src/MissionManager/MissionSettingsItem.h \
src/MissionManager/PlanElementController.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/RallyPoint.h \
...
...
@@ -640,7 +640,7 @@ SOURCES += \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
src/MissionManager/MissionSettings
Complex
Item.cc \
src/MissionManager/MissionSettingsItem.cc \
src/MissionManager/PlanElementController.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/RallyPoint.cc \
...
...
qgroundcontrol.qrc
View file @
cff65ebe
...
...
@@ -36,7 +36,7 @@
<file alias="MainWindowInner.qml">src/ui/MainWindowInner.qml</file>
<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="
PlanView.qml">src/PlanView/PlanView
.qml</file>
<file alias="MixersComponent.qml">src/AutoPilotPlugins/Common/MixersComponent.qml</file>
<file alias="MockLink.qml">src/ui/preferences/MockLink.qml</file>
<file alias="MockLinkSettings.qml">src/ui/preferences/MockLinkSettings.qml</file>
...
...
@@ -47,32 +47,32 @@
<file alias="PX4FlowSensor.qml">src/VehicleSetup/PX4FlowSensor.qml</file>
<file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
<file alias="QGroundControl/Controls/AppMessages.qml">src/QmlControls/AppMessages.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/
MissionEditor
/CameraSection.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/
PlanView
/CameraSection.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
<file alias="QGroundControl/Controls/DropButton.qml">src/QmlControls/DropButton.qml</file>
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
<file alias="QGroundControl/Controls/FactSliderPanel.qml">src/QmlControls/FactSliderPanel.qml</file>
<file alias="QGroundControl/Controls/FlightModeDropdown.qml">src/QmlControls/FlightModeDropdown.qml</file>
<file alias="QGroundControl/Controls/FlightModeMenu.qml">src/QmlControls/FlightModeMenu.qml</file>
<file alias="QGroundControl/Controls/FWLandingPatternMapVisual.qml">src/
MissionEditor
/FWLandingPatternMapVisual.qml</file>
<file alias="QGroundControl/Controls/GeoFenceEditor.qml">src/
MissionEditor
/GeoFenceEditor.qml</file>
<file alias="QGroundControl/Controls/GeoFenceMapVisuals.qml">src/
MissionEditor
/GeoFenceMapVisuals.qml</file>
<file alias="QGroundControl/Controls/FWLandingPatternMapVisual.qml">src/
PlanView
/FWLandingPatternMapVisual.qml</file>
<file alias="QGroundControl/Controls/GeoFenceEditor.qml">src/
PlanView
/GeoFenceEditor.qml</file>
<file alias="QGroundControl/Controls/GeoFenceMapVisuals.qml">src/
PlanView
/GeoFenceMapVisuals.qml</file>
<file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file>
<file alias="QGroundControl/Controls/MainToolBar.qml">src/ui/toolbar/MainToolBar.qml</file>
<file alias="QGroundControl/Controls/MainToolBarIndicators.qml">src/ui/toolbar/MainToolBarIndicators.qml</file>
<file alias="QGroundControl/Controls/MissionCommandDialog.qml">src/QmlControls/MissionCommandDialog.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/
MissionEditor
/MissionItemEditor.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/
PlanView
/MissionItemEditor.qml</file>
<file alias="QGroundControl/Controls/MissionItemIndexLabel.qml">src/QmlControls/MissionItemIndexLabel.qml</file>
<file alias="QGroundControl/Controls/MissionItemMapVisual.qml">src/
MissionEditor
/MissionItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/MissionItemStatus.qml">src/
MissionEditor
/MissionItemStatus.qml</file>
<file alias="QGroundControl/Controls/MissionSettingsMapVisual.qml">src/
MissionEditor
/MissionSettingsMapVisual.qml</file>
<file alias="QGroundControl/Controls/MissionItemMapVisual.qml">src/
PlanView
/MissionItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/MissionItemStatus.qml">src/
PlanView
/MissionItemStatus.qml</file>
<file alias="QGroundControl/Controls/MissionSettingsMapVisual.qml">src/
PlanView
/MissionSettingsMapVisual.qml</file>
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/MultiRotorMotorDisplay.qml">src/QmlControls/MultiRotorMotorDisplay.qml</file>
<file alias="QGroundControl/Controls/OfflineMapButton.qml">src/QmlControls/OfflineMapButton.qml</file>
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="QGroundControl/Controls/PlanToolBar.qml">src/
MissionEditor
/PlanToolBar.qml</file>
<file alias="QGroundControl/Controls/PlanToolBar.qml">src/
PlanView
/PlanToolBar.qml</file>
<file alias="QGroundControl/Controls/QGCButton.qml">src/QmlControls/QGCButton.qml</file>
<file alias="QGroundControl/Controls/QGCCheckBox.qml">src/QmlControls/QGCCheckBox.qml</file>
<file alias="QGroundControl/Controls/QGCColoredImage.qml">src/QmlControls/QGCColoredImage.qml</file>
...
...
@@ -98,17 +98,17 @@
<file alias="QGroundControl/Controls/QGCViewMessage.qml">src/QmlControls/QGCViewMessage.qml</file>
<file alias="QGroundControl/Controls/QGCViewPanel.qml">src/QmlControls/QGCViewPanel.qml</file>
<file alias="QGroundControl/Controls/qmldir">src/QmlControls/QGroundControl.Controls.qmldir</file>
<file alias="QGroundControl/Controls/RallyPointEditorHeader.qml">src/
MissionEditor
/RallyPointEditorHeader.qml</file>
<file alias="QGroundControl/Controls/RallyPointItemEditor.qml">src/
MissionEditor
/RallyPointItemEditor.qml</file>
<file alias="QGroundControl/Controls/RallyPointEditorHeader.qml">src/
PlanView
/RallyPointEditorHeader.qml</file>
<file alias="QGroundControl/Controls/RallyPointItemEditor.qml">src/
PlanView
/RallyPointItemEditor.qml</file>
<file alias="QGroundControl/Controls/RCChannelMonitor.qml">src/QmlControls/RCChannelMonitor.qml</file>
<file alias="QGroundControl/Controls/RoundButton.qml">src/QmlControls/RoundButton.qml</file>
<file alias="QGroundControl/Controls/SectionHeader.qml">src/
MissionEditor
/SectionHeader.qml</file>
<file alias="QGroundControl/Controls/SectionHeader.qml">src/
PlanView
/SectionHeader.qml</file>
<file alias="QGroundControl/Controls/SetupPage.qml">src/AutoPilotPlugins/Common/SetupPage.qml</file>
<file alias="QGroundControl/Controls/SignalStrength.qml">src/ui/toolbar/SignalStrength.qml</file>
<file alias="QGroundControl/Controls/SimpleItemMapVisual.qml">src/
MissionEditor
/SimpleItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/SimpleItemMapVisual.qml">src/
PlanView
/SimpleItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/SliderSwitch.qml">src/QmlControls/SliderSwitch.qml</file>
<file alias="QGroundControl/Controls/SubMenuButton.qml">src/QmlControls/SubMenuButton.qml</file>
<file alias="QGroundControl/Controls/SurveyMapVisual.qml">src/
MissionEditor
/SurveyMapVisual.qml</file>
<file alias="QGroundControl/Controls/SurveyMapVisual.qml">src/
PlanView
/SurveyMapVisual.qml</file>
<file alias="QGroundControl/Controls/VehicleRotationCal.qml">src/QmlControls/VehicleRotationCal.qml</file>
<file alias="QGroundControl/Controls/VehicleSummaryRow.qml">src/QmlControls/VehicleSummaryRow.qml</file>
<file alias="QGroundControl/Controls/ToolStrip.qml">src/QmlControls/ToolStrip.qml</file>
...
...
@@ -147,7 +147,7 @@
<file alias="QGroundControl/FlightMap/QGCCompassWidget.qml">src/FlightMap/Widgets/QGCCompassWidget.qml</file>
<file alias="QGCInstrumentWidget.qml">src/FlightMap/Widgets/QGCInstrumentWidget.qml</file>
<file alias="QGCInstrumentWidgetAlternate.qml">src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml</file>
<file alias="QGroundControl/FlightMap/QGCMapPolygonControls.qml">src/
MissionEditor
/QGCMapPolygonControls.qml</file>
<file alias="QGroundControl/FlightMap/QGCMapPolygonControls.qml">src/
PlanView
/QGCMapPolygonControls.qml</file>
<file alias="QGroundControl/FlightMap/QGCPitchIndicator.qml">src/FlightMap/Widgets/QGCPitchIndicator.qml</file>
<file alias="QGroundControl/FlightMap/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file>
<file alias="QGroundControl/FlightMap/qmldir">src/FlightMap/qmldir</file>
...
...
@@ -168,10 +168,10 @@
<file alias="SerialSettings.qml">src/ui/preferences/SerialSettings.qml</file>
<file alias="SetupParameterEditor.qml">src/VehicleSetup/SetupParameterEditor.qml</file>
<file alias="SetupView.qml">src/VehicleSetup/SetupView.qml</file>
<file alias="SimpleItemEditor.qml">src/
MissionEditor
/SimpleItemEditor.qml</file>
<file alias="SurveyItemEditor.qml">src/
MissionEditor
/SurveyItemEditor.qml</file>
<file alias="FWLandingPatternEditor.qml">src/
MissionEditor
/FWLandingPatternEditor.qml</file>
<file alias="MissionSettingsEditor.qml">src/
MissionEditor
/MissionSettingsEditor.qml</file>
<file alias="SimpleItemEditor.qml">src/
PlanView
/SimpleItemEditor.qml</file>
<file alias="SurveyItemEditor.qml">src/
PlanView
/SurveyItemEditor.qml</file>
<file alias="FWLandingPatternEditor.qml">src/
PlanView
/FWLandingPatternEditor.qml</file>
<file alias="MissionSettingsEditor.qml">src/
PlanView
/MissionSettingsEditor.qml</file>
<file alias="TcpSettings.qml">src/ui/preferences/TcpSettings.qml</file>
<file alias="test.qml">src/test.qml</file>
<file alias="UdpSettings.qml">src/ui/preferences/UdpSettings.qml</file>
...
...
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
cff65ebe
...
...
@@ -34,42 +34,54 @@ FlightMap {
property
var
qgcView
///< QGCView control which contains this map
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
bool
_activeVehicleCoordinateValid
:
_activeVehicle
?
_activeVehicle
.
coordinateValid
:
false
property
var
activeVehicleCoordinate
:
_activeVehicle
?
_activeVehicle
.
coordinate
:
QtPositioning
.
coordinate
()
property
var
_activeVehicleCoordinate
:
_activeVehicle
?
_activeVehicle
.
coordinate
:
QtPositioning
.
coordinate
()
property
var
_gotoHereCoordinate
:
QtPositioning
.
coordinate
()
property
int
_retaskSequence
:
0
property
real
_toolButtonTopMargin
:
parent
.
height
-
ScreenTools
.
availableHeight
+
(
ScreenTools
.
defaultFontPixelHeight
/
2
)
property
bool
_disableVehicleTracking
:
false
property
bool
_keepVehicleCentered
:
_mainIsMap
?
false
:
true
property
bool
_followVehicleSetting
:
true
///< User facing setting for follow vehicle
property
bool
_followVehicle
:
_followVehicleSetting
&&
_activeVehicleCoordinateValid
///< Control map follow vehicle functionality
property
bool
_firstVehiclePosition
:
true
property
bool
_firstVehiclePositionReceived
:
false
property
bool
_userPanned
:
false
Component.onCompleted
:
{
QGroundControl
.
flightMapPosition
=
center
QGroundControl
.
flightMapZoom
=
zoomLevel
possibleCenterToGCSPosition
()
}
// Track last known map position and zoom in settings
onZoomLevelChanged
:
QGroundControl
.
flightMapZoom
=
zoomLevel
onCenterChanged
:
QGroundControl
.
flightMapPosition
=
center
// When the user pans the map we leave things alone until the panRecenterTimer fires
// We move the map to the gcs position id:
// - We don't have a vehicle position yet
// - The user has not futzed with the map
onGcsPositionChanged
:
possibleCenterToGCSPosition
()
function
possibleCenterToGCSPosition
()
{
if
(
!
_firstVehiclePositionReceived
&&
!
_userPanned
&&
gcsPosition
.
isValid
)
{
center
=
gcsPosition
}
}
// When the user pans the map we stop responding to vehicle coordinate updates until the panRecenterTimer fires
Connections
{
target
:
gesture
onPanFinished
:
{
_userPanned
=
true
_disableVehicleTracking
=
true
panRecenterTimer
.
start
()
}
onFlickFinished
:
{
_userPanned
=
true
_disableVehicleTracking
=
true
panRecenterTimer
.
start
()
}
}
onCenterChanged
:
QGroundControl
.
flightMapPosition
=
center
function
pointInRect
(
point
,
rect
)
{
return
point
.
x
>
rect
.
x
&&
point
.
x
<
rect
.
x
+
rect
.
width
&&
...
...
@@ -100,22 +112,22 @@ FlightMap {
}
function
recenterNeeded
()
{
var
vehiclePoint
=
flightMap
.
fromCoordinate
(
activeVehicleCoordinate
,
false
/* clipToViewport */
)
var
vehiclePoint
=
flightMap
.
fromCoordinate
(
_
activeVehicleCoordinate
,
false
/* clipToViewport */
)
var
centerViewport
=
Qt
.
rect
(
0
,
0
,
width
,
height
)
return
!
pointInRect
(
vehiclePoint
,
centerViewport
)
}
function
updateMapToVehiclePosition
()
{
if
(
_
followVehicle
&&
!
_disableVehicleTracking
)
{
if
(
_
activeVehicleCoordinate
.
isValid
&&
!
_disableVehicleTracking
)
{
if
(
_keepVehicleCentered
)
{
_firstVehiclePosition
=
true
flightMap
.
center
=
activeVehicleCoordinate
_firstVehiclePosition
Received
=
true
flightMap
.
center
=
_
activeVehicleCoordinate
}
else
{
if
(
_firstVehiclePosition
)
{
_firstVehiclePosition
=
fals
e
flightMap
.
center
=
activeVehicleCoordinate
if
(
!
_firstVehiclePositionReceived
)
{
_firstVehiclePosition
Received
=
tru
e
flightMap
.
center
=
_
activeVehicleCoordinate
}
else
if
(
recenterNeeded
())
{
animatedMapRecenter
(
flightMap
.
center
,
activeVehicleCoordinate
)
animatedMapRecenter
(
flightMap
.
center
,
_
activeVehicleCoordinate
)
}
}
}
...
...
@@ -266,10 +278,6 @@ FlightMap {
CenterMapDropPanel
{
map
:
_flightMap
fitFunctions
:
mapFitFunctions
showFollowVehicle
:
true
followVehicle
:
_followVehicleSetting
onFollowVehicleChanged
:
_followVehicleSetting
=
followVehicle
}
}
...
...
src/FlightMap/FlightMap.qml
View file @
cff65ebe
...
...
@@ -7,13 +7,6 @@
*
****************************************************************************/
/**
* @file
* @brief QGC Map Background
* @author Gus Grubba <mavlink@grubba.com>
*/
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtLocation
5.3
...
...
@@ -27,34 +20,21 @@ import QGroundControl.ScreenTools 1.0
import
QGroundControl
.
MultiVehicleManager
1.0
import
QGroundControl
.
Vehicle
1.0
import
QGroundControl
.
Mavlink
1.0
import
QGroundControl
.
QGCPositionManager
1.0
Map
{
id
:
_map
zoomLevel
:
QGroundControl
.
flightMapZoom
center
:
QGroundControl
.
flightMapPosition
gesture.flickDeceleration
:
3000
plugin
:
Plugin
{
name
:
"
QGroundControl
"
}
property
string
mapName
:
'
defaultMap
'
property
bool
isSatelliteMap
:
activeMapType
.
name
.
indexOf
(
"
Satellite
"
)
>
-
1
||
activeMapType
.
name
.
indexOf
(
"
Hybrid
"
)
>
-
1
property
var
gcsPosition
:
QtPositioning
.
coordinate
()
readonly
property
real
maxZoomLevel
:
20
property
variant
scaleLengths
:
[
5
,
10
,
25
,
50
,
100
,
150
,
250
,
500
,
1000
,
2000
,
5000
,
10000
,
20000
,
50000
,
100000
,
200000
,
500000
,
1000000
,
2000000
]
function
formatDistance
(
meters
)
{
var
dist
=
Math
.
round
(
meters
)
if
(
dist
>
1000
){
if
(
dist
>
100000
){
dist
=
Math
.
round
(
dist
/
1000
)
}
else
{
dist
=
Math
.
round
(
dist
/
100
)
dist
=
dist
/
10
}
dist
=
dist
+
"
km
"
}
else
{
dist
=
dist
+
"
m
"
}
return
dist
}
function
setVisibleRegion
(
region
)
{
// This works around a bug on Qt where if you set a visibleRegion and then the user moves or zooms the map
...
...
@@ -64,13 +44,18 @@ Map {
_map
.
visibleRegion
=
region
}
zoomLevel
:
18
center
:
QGroundControl
.
lastKnownHomePosition
gesture.flickDeceleration
:
3000
ExclusiveGroup
{
id
:
mapTypeGroup
}
plugin
:
Plugin
{
name
:
"
QGroundControl
"
}
// Update ground station position
Connections
{
target
:
QGroundControl
.
qgcPositionManger
ExclusiveGroup
{
id
:
mapTypeGroup
}
onLastPositionUpdated
:
{
if
(
valid
&&
lastPosition
.
latitude
&&
Math
.
abs
(
lastPosition
.
latitude
)
>
0.001
&&
lastPosition
.
longitude
&&
Math
.
abs
(
lastPosition
.
longitude
)
>
0.001
)
{
gcsPosition
=
QtPositioning
.
coordinate
(
lastPosition
.
latitude
,
lastPosition
.
longitude
)
}
}
}
function
updateActiveMapType
()
{
var
settings
=
QGroundControl
.
settingsManager
.
flightMapSettings
...
...
@@ -99,10 +84,10 @@ Map {
MapQuickItem
{
anchorPoint.x
:
sourceItem
.
anchorPointX
anchorPoint.y
:
sourceItem
.
anchorPointY
visible
:
mainWindow
.
gcsPosition
.
isValid
coordinate
:
mainWindow
.
gcsPosition
visible
:
gcsPosition
.
isValid
coordinate
:
gcsPosition
sourceItem
:
MissionItemIndexLabel
{
label
:
"
Q
"
label
:
"
Q
"
}
}
}
// Map
src/FlightMap/Widgets/CenterMapDropPanel.qml
View file @
cff65ebe
...
...
@@ -25,8 +25,6 @@ ColumnLayout {
property
var
fitFunctions
property
bool
showMission
:
true
property
bool
showAllItems
:
true
property
bool
showFollowVehicle
:
false
property
bool
followVehicle
:
false
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
...
...
@@ -70,7 +68,7 @@ ColumnLayout {
QGCButton
{
text
:
qsTr
(
"
Current Location
"
)
Layout.fillWidth
:
true
enabled
:
mainWindow
.
gcsPosition
.
isValid
&&
!
followVehicleCheckBox
.
checked
enabled
:
mainWindow
.
gcsPosition
.
isValid
onClicked
:
{
dropPanel
.
hide
()
...
...
@@ -81,23 +79,11 @@ ColumnLayout {
QGCButton
{
text
:
qsTr
(
"
Vehicle
"
)
Layout.fillWidth
:
true
enabled
:
_activeVehicle
&&
_activeVehicle
.
latitude
!=
0
&&
_activeVehicle
.
longitude
!=
0
&&
!
followVehicleCheckBox
.
checke
d
enabled
:
_activeVehicle
&&
_activeVehicle
.
coordinate
.
isVali
d
onClicked
:
{
dropPanel
.
hide
()
map
.
center
=
activeVehicle
.
coordinate
}
}
QGCCheckBox
{
id
:
followVehicleCheckBox
text
:
qsTr
(
"
Follow Vehicle
"
)
checked
:
followVehicle
visible
:
showFollowVehicle
onClicked
:
{
dropPanel
.
hide
()
root
.
followVehicle
=
checked
}
}
}
// Column
src/MissionManager/MissionController.cc
View file @
cff65ebe
...
...
@@ -21,7 +21,7 @@
#include "ParameterManager.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "MissionSettings
Complex
Item.h"
#include "MissionSettingsItem.h"
#ifndef __mobile__
#include "MainWindow.h"
...
...
@@ -49,6 +49,7 @@ const int MissionController::_missionFileVersion = 2;
MissionController
::
MissionController
(
QObject
*
parent
)
:
PlanElementController
(
parent
)
,
_visualItems
(
NULL
)
,
_settingsItem
(
NULL
)
,
_firstItemsFromVehicle
(
false
)
,
_missionItemsRequested
(
false
)
,
_queuedSend
(
false
)
...
...
@@ -117,7 +118,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
if
(
_activeVehicle
->
firmwarePlugin
()
->
sendHomePositionToVehicle
()
&&
newMissionItems
.
count
()
!=
0
)
{
// First item is fake home position
_addMissionSettings
(
_activeVehicle
,
newControllerMissionItems
,
false
/* addToCenter */
);
MissionSettings
ComplexItem
*
settingsItem
=
newControllerMissionItems
->
value
<
MissionSettingsComplex
Item
*>
(
0
);
MissionSettings
Item
*
settingsItem
=
newControllerMissionItems
->
value
<
MissionSettings
Item
*>
(
0
);
if
(
!
settingsItem
)
{
qWarning
()
<<
"First item is not settings item"
;
return
;
...
...
@@ -133,10 +134,11 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
_deinitAllVisualItems
();
_visualItems
->
deleteLater
();
_settingsItem
=
NULL
;
_visualItems
=
newControllerMissionItems
;
if
(
!
_activeVehicle
->
firmwarePlugin
()
->
sendHomePositionToVehicle
()
||
_visualItems
->
count
()
==
0
)
{
_addMissionSettings
(
_activeVehicle
,
_visualItems
,
true
/* addToCenter */
);
_addMissionSettings
(
_activeVehicle
,
_visualItems
,
_visualItems
->
count
()
>
0
/* addToCenter */
);
}
_missionItemsRequested
=
false
;
...
...
@@ -187,7 +189,7 @@ bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMission
}
// Mission settings has a special case for end mission action
MissionSettings
ComplexItem
*
settingsItem
=
visualMissionItems
->
value
<
MissionSettingsComplex
Item
*>
(
0
);
MissionSettings
Item
*
settingsItem
=
visualMissionItems
->
value
<
MissionSettings
Item
*>
(
0
);
if
(
settingsItem
)
{
endActionSet
=
settingsItem
->
addMissionEndAction
(
rgMissionItems
,
lastSeqNum
+
1
,
missionItemParent
);
}
...
...
@@ -289,6 +291,7 @@ void MissionController::removeAll(void)
if
(
_visualItems
)
{
_deinitAllVisualItems
();
_visualItems
->
deleteLater
();
_settingsItem
=
NULL
;
_visualItems
=
new
QmlObjectListModel
(
this
);
_addMissionSettings
(
_activeVehicle
,
_visualItems
,
false
/* addToCenter */
);
_initAllVisualItems
();
...
...
@@ -412,7 +415,7 @@ bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObje
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
vehicle
,
visualItems
);
if
(
item
->
load
(
json
[
_jsonPlannedHomePositionKey
].
toObject
(),
0
,
errorString
))
{
MissionSettings
ComplexItem
*
settingsItem
=
new
MissionSettingsComplex
Item
(
vehicle
,
visualItems
);
MissionSettings
Item
*
settingsItem
=
new
MissionSettings
Item
(
vehicle
,
visualItems
);
settingsItem
->
setCoordinate
(
item
->
coordinate
());
visualItems
->
insert
(
0
,
settingsItem
);
item
->
deleteLater
();
...
...
@@ -459,7 +462,7 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
setRawValue
(
json
[
_jsonHoverSpeedKey
].
toDouble
());
}
MissionSettings
ComplexItem
*
settingsItem
=
new
MissionSettingsComplex
Item
(
vehicle
,
visualItems
);
MissionSettings
Item
*
settingsItem
=
new
MissionSettings
Item
(
vehicle
,
visualItems
);
settingsItem
->
setCoordinate
(
homeCoordinate
);
visualItems
->
insert
(
0
,
settingsItem
);
qCDebug
(
MissionControllerLog
)
<<
"plannedHomePosition"
<<
homeCoordinate
;
...
...
@@ -523,9 +526,9 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
nextSequenceNumber
=
landingItem
->
lastSequenceNumber
()
+
1
;
qCDebug
(
MissionControllerLog
)
<<
"FW Landing Pattern load complete: nextSequenceNumber"
<<
nextSequenceNumber
;
visualItems
->
append
(
landingItem
);
}
else
if
(
complexItemType
==
MissionSettings
Complex
Item
::
jsonComplexItemTypeValue
)
{
}
else
if
(
complexItemType
==
MissionSettingsItem
::
jsonComplexItemTypeValue
)
{
qCDebug
(
MissionControllerLog
)
<<
"Loading Mission Settings: nextSequenceNumber"
<<
nextSequenceNumber
;
MissionSettings
ComplexItem
*
settingsItem
=
new
MissionSettingsComplex
Item
(
vehicle
,
visualItems
);
MissionSettings
Item
*
settingsItem
=
new
MissionSettings
Item
(
vehicle
,
visualItems
);
if
(
!
settingsItem
->
load
(
itemObject
,
nextSequenceNumber
++
,
errorString
))
{
return
false
;
}
...
...
@@ -630,6 +633,7 @@ void MissionController::loadFromFile(const QString& filename)
if
(
_visualItems
)
{
_deinitAllVisualItems
();
_visualItems
->
deleteLater
();
_settingsItem
=
NULL
;
}
_visualItems
=
newVisualItems
;
...
...
@@ -719,9 +723,9 @@ void MissionController::saveToFile(const QString& filename)
// Mission settings
MissionSettings
ComplexItem
*
settingsItem
=
_visualItems
->
value
<
MissionSettingsComplex
Item
*>
(
0
);
MissionSettings
Item
*
settingsItem
=
_visualItems
->
value
<
MissionSettings
Item
*>
(
0
);
if
(
!
settingsItem
)
{
qWarning
()
<<
"First item is not MissionSettings
Complex
Item"
;
qWarning
()
<<
"First item is not MissionSettingsItem"
;
return
;
}
QJsonValue
coordinateValue
;
...
...
@@ -828,13 +832,7 @@ void MissionController::_recalcWaypointLines(void)
bool
firstCoordinateItem
=
true
;
VisualMissionItem
*
lastCoordinateItem
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
0
));
MissionSettingsComplexItem
*
settingsItem
=
qobject_cast
<
MissionSettingsComplexItem
*>
(
lastCoordinateItem
);
if
(
!
settingsItem
)
{
qWarning
()
<<
"First item is not MissionSettingsComplexItem"
;
}
bool
showHomePosition
=
settingsItem
->
showHomePosition
();
bool
showHomePosition
=
_settingsItem
->
coordinate
().
isValid
();
qCDebug
(
MissionControllerLog
)
<<
"_recalcWaypointLines"
;
...
...
@@ -859,7 +857,7 @@ void MissionController::_recalcWaypointLines(void)
if
(
!
item
->
isStandaloneCoordinate
())
{
firstCoordinateItem
=
false
;
VisualItemPair
pair
(
lastCoordinateItem
,
item
);
if
(
lastCoordinateItem
!=
settingsItem
||
(
showHomePosition
&&
linkBackToHome
))
{
if
(
lastCoordinateItem
!=
_
settingsItem
||
(
showHomePosition
&&
linkBackToHome
))
{
if
(
old_table
.
contains
(
pair
))
{
// Do nothing, this segment already exists and is wired up
_linesTable
[
pair
]
=
old_table
.
take
(
pair
);
...
...
@@ -911,13 +909,8 @@ void MissionController::_recalcMissionFlightStatus()
bool
firstCoordinateItem
=
true
;
VisualMissionItem
*
lastCoordinateItem
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
0
));
MissionSettingsComplexItem
*
settingsItem
=
qobject_cast
<
MissionSettingsComplexItem
*>
(
lastCoordinateItem
);
if
(
!
settingsItem
)
{
qWarning
()
<<
"First item is not MissionSettingsComplexItem"
;
}
bool
showHomePosition
=
settingsItem
->
showHomePosition
();
bool
showHomePosition
=
_settingsItem
->
coordinate
().
isValid
();
qCDebug
(
MissionControllerLog
)
<<
"_recalcMissionFlightStatus"
;
...
...
@@ -932,8 +925,8 @@ void MissionController::_recalcMissionFlightStatus()
double
minAltSeen
=
0.0
;
double
maxAltSeen
=
0.0
;
const
double
homePositionAltitude
=
settingsItem
->
coordinate
().
altitude
();
minAltSeen
=
maxAltSeen
=
settingsItem
->
coordinate
().
altitude
();
const
double
homePositionAltitude
=
_
settingsItem
->
coordinate
().
altitude
();
minAltSeen
=
maxAltSeen
=
_
settingsItem
->
coordinate
().
altitude
();
double
lastVehicleYaw
=
0
;
...
...
@@ -1050,7 +1043,7 @@ void MissionController::_recalcMissionFlightStatus()
if
(
!
item
->
isStandaloneCoordinate
())
{
firstCoordinateItem
=
false
;
if
(
lastCoordinateItem
!=
settingsItem
||
linkBackToHome
)
{
if
(
lastCoordinateItem
!=
_
settingsItem
||
linkBackToHome
)
{
// This is a subsequent waypoint or we are forcing the first waypoint back to home
double
azimuth
,
distance
,
altDifference
;
...
...
@@ -1060,7 +1053,7 @@ void MissionController::_recalcMissionFlightStatus()
item
->
setDistance
(
distance
);
_missionFlightStatus
.
totalDistance
+=
distance
;
_missionFlightStatus
.
maxTelemetryDistance
=
qMax
(
_missionFlightStatus
.
maxTelemetryDistance
,
_calcDistanceToHome
(
item
,
settingsItem
));
_missionFlightStatus
.
maxTelemetryDistance
=
qMax
(
_missionFlightStatus
.
maxTelemetryDistance
,
_calcDistanceToHome
(
item
,
_
settingsItem
));
// Calculate time/distance
double
hoverTime
=
distance
/
_missionFlightStatus
.
hoverSpeed
;
...
...
@@ -1093,7 +1086,7 @@ void MissionController::_recalcMissionFlightStatus()
// Add in distance/time inside complex items as well
double
distance
=
complexItem
->
complexDistance
();
_missionFlightStatus
.
totalDistance
+=
distance
;
_missionFlightStatus
.
maxTelemetryDistance
=
qMax
(
_missionFlightStatus
.
maxTelemetryDistance
,
complexItem
->
greatestDistanceTo
(
settings
Item
->
exitCoordinate
()));
_missionFlightStatus
.
maxTelemetryDistance
=
qMax
(
_missionFlightStatus
.
maxTelemetryDistance
,
complexItem
->
greatestDistanceTo
(
complex
Item
->
exitCoordinate
()));
double
hoverTime
=
_missionFlightStatus
.
totalDistance
/
_missionFlightStatus
.
hoverSpeed
;
double
cruiseTime
=
_missionFlightStatus
.
totalDistance
/
_missionFlightStatus
.
cruiseSpeed
;
...
...
@@ -1191,8 +1184,26 @@ void MissionController::_recalcChildItems(void)
}
}
void
MissionController
::
_setPlannedHomePositionFromFirstCoordinate
(
void
)
{
if
(
_settingsItem
->
coordinate
().
isValid
())
{
return
;
}
// Set the planned home position to be a deltae from first coordinate
for
(
int
i
=
1
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
item
=
_visualItems
->
value
<
VisualMissionItem
*>
(
i
);
if
(
item
->
specifiesCoordinate
())
{
_settingsItem
->
setCoordinate
(
item
->
coordinate
().
atDistanceAndAzimuth
(
30
,
0
));
}
}
}
void
MissionController
::
_recalcAll
(
void
)
{
_setPlannedHomePositionFromFirstCoordinate
();
_recalcSequence
();
_recalcChildItems
();
_recalcWaypointLines
();
...
...
@@ -1201,27 +1212,20 @@ void MissionController::_recalcAll(void)
/// Initializes a new set of mission items
void
MissionController
::
_initAllVisualItems
(
void
)
{
MissionSettingsComplexItem
*
settingsItem
=
NULL
;
// Setup home position at index 0
settingsItem
=
qobject_cast
<
MissionSettingsComplex
Item
*>
(
_visualItems
->
get
(
0
));
if
(
!
settingsItem
)
{
qWarning
()
<<
"First item not MissionSettings
Complex
Item"
;
_settingsItem
=
qobject_cast
<
MissionSettings
Item
*>
(
_visualItems
->
get
(
0
));
if
(
!
_
settingsItem
)
{
qWarning
()
<<
"First item not MissionSettingsItem"
;
return
;
}
_settingsItem
->
setIsCurrentItem
(
true
);
settingsItem
->
setShowHomePosition
(
_editMode
);
settingsItem
->
setIsCurrentItem
(
true
);
if
(
!
_editMode
&&
_activeVehicle
&&
_activeVehicle
->
homePositionAvailable
())
{
settingsItem
->
setCoordinate
(
_activeVehicle
->
homePosition
());
settingsItem
->
setShowHomePosition
(
true
);
if
(
!
_editMode
&&
_activeVehicle
)
{
_settingsItem
->
setCoordinate
(
_activeVehicle
->
homePosition
());
}
emit
plannedHomePositionChanged
(
plannedHomePosition
());
connect
(
settingsItem
,
&
VisualMissionItem
::
coordinateChanged
,
this
,
&
MissionController
::
_homeCoordinateChanged
);
connect
(
_settingsItem
,
&
MissionSettingsItem
::
coordinateChanged
,
this
,
&
MissionController
::
_recalcAll
);
for
(
int
i
=
0
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
...
...
@@ -1298,7 +1302,6 @@ void MissionController::_activeVehicleBeingRemoved(void)
disconnect
(
missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
MissionController
::
_newMissionItemsAvailableFromVehicle
);
disconnect
(
missionManager
,
&
MissionManager
::
inProgressChanged
,
this
,
&
MissionController
::
_inProgressChanged
);
disconnect
(
missionManager
,
&
MissionManager
::
currentItemChanged
,
this
,
&
MissionController
::
_currentMissionItemChanged
);
disconnect
(
_activeVehicle
,
&
Vehicle
::
homePositionAvailableChanged
,
this
,
&
MissionController
::
_activeVehicleHomePositionAvailableChanged
);
disconnect
(
_activeVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionController
::
_activeVehicleHomePositionChanged
);
// We always remove all items on vehicle change. This leaves a user model hole:
...
...
@@ -1317,7 +1320,6 @@ void MissionController::_activeVehicleSet(void)
connect
(
missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
MissionController
::
_newMissionItemsAvailableFromVehicle
);
connect
(
missionManager
,
&
MissionManager
::
inProgressChanged
,
this
,
&
MissionController
::
_inProgressChanged
);
connect
(
missionManager
,
&
MissionManager
::
currentItemChanged
,
this
,
&
MissionController
::
_currentMissionItemChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionAvailableChanged
,
this
,
&
MissionController
::
_activeVehicleHomePositionAvailableChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionController
::
_activeVehicleHomePositionChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
defaultCruiseSpeedChanged
,
this
,
&
MissionController
::
_recalcMissionFlightStatus
);
connect
(
_activeVehicle
,
&
Vehicle
::
defaultHoverSpeedChanged
,
this
,
&
MissionController
::
_recalcMissionFlightStatus
);
...
...
@@ -1330,40 +1332,18 @@ void MissionController::_activeVehicleSet(void)
}
_activeVehicleHomePositionChanged
(
_activeVehicle
->
homePosition
());
_activeVehicleHomePositionAvailableChanged
(
_activeVehicle
->
homePositionAvailable
());
emit
complexMissionItemNamesChanged
();
}
void
MissionController
::
_activeVehicleHomePositionAvailableChanged
(
bool
homePositionAvailable
)
{
if
(
!
_editMode
&&
_visualItems
)
{
MissionSettingsComplexItem
*
settingsItem
=
qobject_cast
<
MissionSettingsComplexItem
*>
(
_visualItems
->
get
(
0
));
if
(
settingsItem
)
{
settingsItem
->
setShowHomePosition
(
homePositionAvailable
);
emit
plannedHomePositionChanged
(
plannedHomePosition
());
_recalcWaypointLines
();
}
else
{
qWarning
()
<<
"First item is not MissionSettingsComplexItem"
;
}
}
}
void
MissionController
::
_activeVehicleHomePositionChanged
(
const
QGeoCoordinate
&
homePosition
)
{
if
(
!
_editMode
&&
_visualItems
)
{
MissionSettings
ComplexItem
*
settingsItem
=
qobject_cast
<
MissionSettingsComplex
Item
*>
(
_visualItems
->
get
(
0
));
if
(
_visualItems
)
{
MissionSettings
Item
*
settingsItem
=
qobject_cast
<
MissionSettings
Item
*>
(
_visualItems
->
get
(
0
));
if
(
settingsItem
)
{
if
(
settingsItem
->
coordinate
()
!=
homePosition
)
{
settingsItem
->
setCoordinate
(
homePosition
);
settingsItem
->
setShowHomePosition
(
true
);
qCDebug
(
MissionControllerLog
)
<<
"Home position update"
<<
homePosition
;
emit
plannedHomePositionChanged
(
plannedHomePosition
());
_recalcWaypointLines
();
}
settingsItem
->
setCoordinate
(
homePosition
);
}
else
{
qWarning
()
<<
"First item is not MissionSettings
Complex
Item"
;
qWarning
()
<<
"First item is not MissionSettingsItem"
;
}
}
}
...
...
@@ -1479,46 +1459,44 @@ double MissionController::_normalizeLon(double lon)
/// Add the Mission Settings complex item to the front of the items
void
MissionController
::
_addMissionSettings
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualItems
,
bool
addToCenter
)
{
bool
homePositionSet
=
false
;
MissionSettingsItem
*
settingsItem
=
new
MissionSettingsItem
(
vehicle
,
visualItems
)
;
MissionSettingsComplexItem
*
settingsItem
=
new
MissionSettingsComplexItem
(
vehicle
,
visualItems
);
visualItems
->
insert
(
0
,
settingsItem
);
if
(
visualItems
->
count
()
>
1
&&
addToCenter
)
{
double
north
=
0.0
;
double
south
=
0.0
;
double
east
=
0.0
;
double
west
=
0.0
;
bool
firstCoordSet
=
false
;
for
(
int
i
=
1
;
i
<
visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
visualItems
->
get
(
i
));
if
(
item
->
specifiesCoordinate
())
{
if
(
firstCoordSet
)
{
double
lat
=
_normalizeLat
(
item
->
coordinate
().
latitude
());
double
lon
=
_normalizeLon
(
item
->
coordinate
().
longitude
());
north
=
fmax
(
north
,
lat
);
south
=
fmin
(
south
,
lat
);
east
=
fmax
(
east
,
lon
);
west
=
fmin
(
west
,
lon
);
}
else
{
firstCoordSet
=
true
;
north
=
_normalizeLat
(
item
->
coordinate
().
latitude
());
south
=
north
;
east
=
_normalizeLon
(
item
->
coordinate
().
longitude
());
west
=
east
;
if
(
addToCenter
)
{
if
(
visualItems
->
count
()
>
1
)
{
double
north
=
0.0
;
double
south
=
0.0
;
double
east
=
0.0
;
double
west
=
0.0
;
bool
firstCoordSet
=
false
;