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
02925e1e
Commit
02925e1e
authored
Mar 11, 2020
by
DoinLakeFlyer
Browse files
Options
Browse Files
Download
Plain Diff
parents
08fe9ca3
2a250a6c
Changes
47
Hide whitespace changes
Inline
Side-by-side
Showing
47 changed files
with
273 additions
and
142 deletions
+273
-142
.travis.yml
.travis.yml
+2
-0
ChangeLog.md
ChangeLog.md
+10
-0
QGCSetup.pri
QGCSetup.pri
+0
-2
msvcp140.dll
deploy/msvcp140.dll
+0
-0
msvcp140_1.dll
deploy/msvcp140_1.dll
+0
-0
msvcp140_2.dll
deploy/msvcp140_2.dll
+0
-0
qgroundcontrol_installer.nsi
deploy/qgroundcontrol_installer.nsi
+1
-2
vcruntime140.dll
deploy/vcruntime140.dll
+0
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+1
-2
PreFlightSensorsHealthCheck.qml
src/FlightDisplay/PreFlightSensorsHealthCheck.qml
+1
-1
MapFitFunctions.qml
src/FlightMap/Widgets/MapFitFunctions.qml
+5
-6
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+15
-15
FWLandingPatternTest.cc
src/MissionManager/FWLandingPatternTest.cc
+2
-2
MissionController.cc
src/MissionManager/MissionController.cc
+24
-8
MissionController.h
src/MissionManager/MissionController.h
+8
-2
MissionItemTest.cc
src/MissionManager/MissionItemTest.cc
+2
-2
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+15
-7
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+1
-2
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+1
-1
SurveyComplexItem.cc
src/MissionManager/SurveyComplexItem.cc
+5
-0
TakeoffMissionItem.cc
src/MissionManager/TakeoffMissionItem.cc
+16
-8
TakeoffMissionItem.h
src/MissionManager/TakeoffMissionItem.h
+2
-2
TransectStyleComplexItem.cc
src/MissionManager/TransectStyleComplexItem.cc
+13
-1
MP 19.prj
src/MissionManager/UnitTest/MP 19.prj
+1
-0
MP 19.shp
src/MissionManager/UnitTest/MP 19.shp
+0
-0
MP 19.shx
src/MissionManager/UnitTest/MP 19.shx
+0
-0
MP Bonus.prj
src/MissionManager/UnitTest/MP Bonus.prj
+1
-0
MP Bonus.shp
src/MissionManager/UnitTest/MP Bonus.shp
+0
-0
MP Bonus.shx
src/MissionManager/UnitTest/MP Bonus.shx
+0
-0
Sarah's Farm.prj
src/MissionManager/UnitTest/Sarah's Farm.prj
+1
-0
Sarah's Farm.shp
src/MissionManager/UnitTest/Sarah's Farm.shp
+0
-0
Sarah's Farm.shx
src/MissionManager/UnitTest/Sarah's Farm.shx
+0
-0
PlanView.qml
src/PlanView/PlanView.qml
+1
-1
QGCFileDialog.qml
src/QmlControls/QGCFileDialog.qml
+6
-6
QGCFileDialogController.cc
src/QmlControls/QGCFileDialogController.cc
+15
-7
QGCFileDialogController.h
src/QmlControls/QGCFileDialogController.h
+2
-2
ToolStrip.qml
src/QmlControls/ToolStrip.qml
+4
-2
PlanView.SettingsGroup.json
src/Settings/PlanView.SettingsGroup.json
+6
-0
PlanViewSettings.cc
src/Settings/PlanViewSettings.cc
+1
-0
PlanViewSettings.h
src/Settings/PlanViewSettings.h
+1
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+53
-24
Vehicle.h
src/Vehicle/Vehicle.h
+12
-7
FirmwareUpgrade.qml
src/VehicleSetup/FirmwareUpgrade.qml
+1
-2
FirmwareUpgradeController.cc
src/VehicleSetup/FirmwareUpgradeController.cc
+19
-24
FirmwareUpgradeController.h
src/VehicleSetup/FirmwareUpgradeController.h
+2
-0
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+21
-3
MainToolBar.qml
src/ui/toolbar/MainToolBar.qml
+2
-1
No files found.
.travis.yml
View file @
02925e1e
...
...
@@ -241,6 +241,7 @@ deploy:
# deploy tagged installers to s3 latest/
-
provider
:
s3
edge
:
true
# Use V2 provider to work around V1 bug
access_key_id
:
AKIAIVORNALE7NHD3T6Q
secret_access_key
:
secure
:
BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4=
...
...
@@ -283,6 +284,7 @@ deploy:
on
:
tags
:
true
condition
:
$CONFIG = installer
condition
:
$SPEC != macx-clang
# GitHub OSX deploy broken due to travis problem
notifications
:
webhooks
:
...
...
ChangeLog.md
View file @
02925e1e
...
...
@@ -8,6 +8,14 @@ Note: This file only contains high level features or important fixes.
## 4.0
### 4.0.3 - Not yet released
### 4.0.3 - Not yet released
*
Plan: Add setting for takeoff item not required
*
Plan: Takeoff item must be added prior to allowing other item types to enable
### 4.0.2 - Stable
*
Fix Mavlink V2 protocol negotation based on capability bits
...
...
@@ -18,6 +26,8 @@ Note: This file only contains high level features or important fixes.
*
Fix ArduPilot current mission item tracking in Fly view
*
Fix ADSB vehicle display
*
Fix map positioning bug in Plan view
*
Fix Windows 0xcc000007b startup error causes by incorrect VC runtimes being installed.
### 4.0.0
...
...
QGCSetup.pri
View file @
02925e1e
...
...
@@ -79,8 +79,6 @@ WindowsBuild {
# Copy Visual Studio DLLs
# Note that this is only done for release because the debugging versions of these DLLs cannot be redistributed.
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\msvcp140.dll\" \"$$DESTDIR_WIN\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\msvcp140_1.dll\" \"$$DESTDIR_WIN\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\msvcp140_2.dll\" \"$$DESTDIR_WIN\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\vcruntime140.dll\" \"$$DESTDIR_WIN\"
}
...
...
deploy/msvcp140.dll
View file @
02925e1e
No preview for this file type
deploy/msvcp140_1.dll
deleted
100644 → 0
View file @
08fe9ca3
File deleted
deploy/msvcp140_2.dll
deleted
100644 → 0
View file @
08fe9ca3
File deleted
deploy/qgroundcontrol_installer.nsi
View file @
02925e1e
...
...
@@ -71,8 +71,7 @@ check64BitUninstall:
StrCmp $R0 "" doInstall
doUninstall:
DetailPrint "Uninstalling previous version..."
ExecWait "$R0 /S -LEAVE_DATA=1"
DetailPrint "Uninstalling previous version..." ExecWait "$R0 /S -LEAVE_DATA=1 _?=$INSTDIR"
IntCmp $0 0 doInstall
MessageBox MB_OK|MB_ICONEXCLAMATION \
...
...
deploy/vcruntime140.dll
View file @
02925e1e
No preview for this file type
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
02925e1e
...
...
@@ -482,14 +482,13 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
void
PX4FirmwarePlugin
::
startMission
(
Vehicle
*
vehicle
)
{
if
(
_setFlightModeAndValidate
(
vehicle
,
missionFlightMode
()))
{
if
(
!
_armVehicleAndValidate
(
vehicle
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to start mission: Vehicle rejected arming."
));
return
;
}
}
else
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to start mission: Vehicle not
ready."
));
qgcApp
()
->
showMessage
(
tr
(
"Unable to start mission: Vehicle not
changing to %1 flight mode."
).
arg
(
missionFlightMode
()
));
}
}
...
...
src/FlightDisplay/PreFlightSensorsHealthCheck.qml
View file @
02925e1e
...
...
@@ -17,7 +17,7 @@ PreFlightCheckButton {
name
:
qsTr
(
"
Sensors
"
)
telemetryFailure
:
_unhealthySensors
&
_allCheckedSensors
property
int
_unhealthySensors
:
activeVehicle
?
activeVehicle
.
sensorsUnhealthyBits
:
0
property
int
_unhealthySensors
:
activeVehicle
?
activeVehicle
.
sensorsUnhealthyBits
:
1
property
int
_allCheckedSensors
:
Vehicle
.
SysStatusSensor3dMag
|
Vehicle
.
SysStatusSensor3dAccel
|
Vehicle
.
SysStatusSensor3dGyro
|
...
...
src/FlightMap/Widgets/MapFitFunctions.qml
View file @
02925e1e
...
...
@@ -41,7 +41,7 @@ Item {
/// Normalize longitude to range: 0 to 360, W to E
function
normalizeLon
(
lon
)
{
return
lon
+
180.0
return
lon
+
180.0
}
/// Fits the visible region of the map to inclues all of the specified coordinates. If no coordinates
...
...
@@ -64,12 +64,12 @@ Item {
for
(
var
i
=
1
;
i
<
coordList
.
length
;
i
++
)
{
var
lat
=
coordList
[
i
].
latitude
var
lon
=
coordList
[
i
].
longitude
if
(
isNaN
(
lat
)
||
lat
==
0
||
isNa
n
(
lon
)
||
lon
==
0
)
{
if
(
isNaN
(
lat
)
||
lat
==
0
||
isNa
N
(
lon
)
||
lon
==
0
)
{
// Be careful of invalid coords which can happen when items are not yet complete
continue
}
lat
=
normalizeLat
(
lat
)
lon
=
normalizeLon
(
l
at
)
lon
=
normalizeLon
(
l
on
)
north
=
Math
.
max
(
north
,
lat
)
south
=
Math
.
min
(
south
,
lat
)
east
=
Math
.
max
(
east
,
lon
)
...
...
@@ -77,8 +77,8 @@ Item {
}
// Expand the coordinate bounding rect to make room for the tools around the edge of the map
var
latDegreesPerPixel
=
(
north
-
south
)
/
mapFitViewport
.
width
var
lonDegreesPerPixel
=
(
east
-
west
)
/
mapFitViewport
.
height
var
latDegreesPerPixel
=
(
north
-
south
)
/
mapFitViewport
.
height
var
lonDegreesPerPixel
=
(
east
-
west
)
/
mapFitViewport
.
width
north
=
Math
.
min
(
north
+
(
mapFitViewport
.
y
*
latDegreesPerPixel
),
180
)
south
=
Math
.
max
(
south
-
((
map
.
height
-
mapFitViewport
.
bottom
)
*
latDegreesPerPixel
),
0
)
west
=
Math
.
max
(
west
-
(
mapFitViewport
.
x
*
lonDegreesPerPixel
),
0
)
...
...
@@ -94,7 +94,6 @@ Item {
var
topLeftCoord
=
QtPositioning
.
coordinate
(
north
-
90.0
,
west
-
180.0
)
var
bottomRightCoord
=
QtPositioning
.
coordinate
(
south
-
90.0
,
east
-
180.0
)
map
.
setVisibleRegion
(
QtPositioning
.
rectangle
(
topLeftCoord
,
bottomRightCoord
))
}
function
addMissionItemCoordsForFit
(
coordList
)
{
...
...
src/MissionManager/CameraSectionTest.cc
View file @
02925e1e
...
...
@@ -592,7 +592,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Check for a scan success
SimpleMissionItem
*
newValidGimbalItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidGimbalItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidGimbalItem
->
missionItem
()
=
_validGimbalItem
->
missionItem
();
visualItems
.
append
(
newValidGimbalItem
);
scanIndex
=
0
;
...
...
@@ -676,7 +676,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
// Check for a scan success
SimpleMissionItem
*
newValidCameraModeItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidCameraModeItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidCameraModeItem
->
missionItem
()
=
_validCameraPhotoModeItem
->
missionItem
();
visualItems
.
append
(
newValidCameraModeItem
);
scanIndex
=
0
;
...
...
@@ -735,7 +735,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
*/
SimpleMissionItem
*
newValidTimeItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidTimeItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidTimeItem
->
missionItem
()
=
_validTimeItem
->
missionItem
();
visualItems
.
append
(
newValidTimeItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
...
...
@@ -776,7 +776,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
Mission Param #7 Empty
*/
SimpleMissionItem
*
newValidDistanceItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidDistanceItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidDistanceItem
->
missionItem
()
=
_validDistanceItem
->
missionItem
();
visualItems
.
append
(
newValidDistanceItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
...
...
@@ -862,7 +862,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
Mission Param #3 Reserved
*/
SimpleMissionItem
*
newValidStartVideoItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidStartVideoItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidStartVideoItem
->
missionItem
()
=
_validStartVideoItem
->
missionItem
();
visualItems
.
append
(
newValidStartVideoItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
...
...
@@ -898,7 +898,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
Mission Param #1 Reserved (Set to 0)
*/
SimpleMissionItem
*
newValidStopVideoItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidStopVideoItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidStopVideoItem
->
missionItem
()
=
_validStopVideoItem
->
missionItem
();
visualItems
.
append
(
newValidStopVideoItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
...
...
@@ -936,8 +936,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
_commonScanTest
(
_cameraSection
);
SimpleMissionItem
*
newValidStopDistanceItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidStopTimeItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidStopDistanceItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
SimpleMissionItem
*
newValidStopTimeItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidStopDistanceItem
->
missionItem
()
=
_validStopDistanceItem
->
missionItem
();
newValidStopTimeItem
->
missionItem
()
=
_validStopTimeItem
->
missionItem
();
visualItems
.
append
(
newValidStopDistanceItem
);
...
...
@@ -950,8 +950,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
// Out of order commands
SimpleMissionItem
validStopDistanceItem
(
_masterController
,
false
/* flyView */
,
nullptr
);
SimpleMissionItem
validStopTimeItem
(
_masterController
,
false
/* flyView */
,
nullptr
);
SimpleMissionItem
validStopDistanceItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
nullptr
);
SimpleMissionItem
validStopTimeItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
nullptr
);
validStopDistanceItem
.
missionItem
()
=
_validStopDistanceItem
->
missionItem
();
validStopTimeItem
.
missionItem
()
=
_validStopTimeItem
->
missionItem
();
visualItems
.
append
(
&
validStopTimeItem
);
...
...
@@ -979,7 +979,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
Mission Param #4 0 Unused sequence id
*/
SimpleMissionItem
*
newValidTakePhotoItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
newValidTakePhotoItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
newValidTakePhotoItem
->
missionItem
()
=
_validTakePhotoItem
->
missionItem
();
visualItems
.
append
(
newValidTakePhotoItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
...
...
@@ -1051,9 +1051,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Camera action followed by gimbal/mode
for
(
SimpleMissionItem
*
actionItem
:
rgActionItems
)
{
for
(
SimpleMissionItem
*
cameraItem
:
rgCameraItems
)
{
SimpleMissionItem
*
item1
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
item1
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
item1
->
missionItem
()
=
actionItem
->
missionItem
();
SimpleMissionItem
*
item2
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
item2
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
item2
->
missionItem
()
=
cameraItem
->
missionItem
();
visualItems
.
append
(
item1
);
visualItems
.
append
(
item2
);
...
...
@@ -1072,9 +1072,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Gimbal/Mode followed by camera action
for
(
SimpleMissionItem
*
actionItem
:
rgCameraItems
)
{
for
(
SimpleMissionItem
*
cameraItem
:
rgActionItems
)
{
SimpleMissionItem
*
item1
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
item1
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
item1
->
missionItem
()
=
actionItem
->
missionItem
();
SimpleMissionItem
*
item2
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
this
);
SimpleMissionItem
*
item2
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
this
);
item2
->
missionItem
()
=
cameraItem
->
missionItem
();
visualItems
.
append
(
item1
);
visualItems
.
append
(
item2
);
...
...
src/MissionManager/FWLandingPatternTest.cc
View file @
02925e1e
...
...
@@ -89,7 +89,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void)
QmlObjectListModel
*
simpleItems
=
new
QmlObjectListModel
(
this
);
for
(
MissionItem
*
item
:
rgMissionItems
)
{
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
simpleItems
);
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
simpleItems
);
simpleItem
->
missionItem
()
=
*
item
;
simpleItems
->
append
(
simpleItem
);
}
...
...
@@ -110,7 +110,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void)
_fwItem
->
appendMissionItems
(
rgMissionItems
,
this
);
simpleItems
=
new
QmlObjectListModel
(
this
);
for
(
MissionItem
*
item
:
rgMissionItems
)
{
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
simpleItems
);
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
simpleItems
);
simpleItem
->
missionItem
()
=
*
item
;
simpleItems
->
append
(
simpleItem
);
}
...
...
src/MissionManager/MissionController.cc
View file @
02925e1e
...
...
@@ -31,6 +31,7 @@
#include "KML.h"
#include "QGCCorePlugin.h"
#include "TakeoffMissionItem.h"
#include "PlanViewSettings.h"
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes
...
...
@@ -62,12 +63,15 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
,
_controllerVehicle
(
masterController
->
controllerVehicle
())
,
_managerVehicle
(
masterController
->
managerVehicle
())
,
_missionManager
(
masterController
->
managerVehicle
()
->
missionManager
())
,
_planViewSettings
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
planViewSettings
())
,
_appSettings
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
())
{
_resetMissionFlightStatus
();
_updateTimer
.
setSingleShot
(
true
);
connect
(
&
_updateTimer
,
&
QTimer
::
timeout
,
this
,
&
MissionController
::
_updateTimeout
);
connect
(
_planViewSettings
->
takeoffItemNotRequired
(),
&
Fact
::
rawValueChanged
,
this
,
&
MissionController
::
_takeoffItemNotRequiredChanged
);
}
MissionController
::~
MissionController
()
...
...
@@ -337,7 +341,7 @@ int MissionController::_nextSequenceNumber(void)
VisualMissionItem
*
MissionController
::
_insertSimpleMissionItemWorker
(
QGeoCoordinate
coordinate
,
MAV_CMD
command
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
int
sequenceNumber
=
_nextSequenceNumber
();
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
this
);
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
false
/* forLoad */
,
this
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
newItem
->
setCoordinate
(
coordinate
);
newItem
->
setCommand
(
command
);
...
...
@@ -651,7 +655,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
MissionSettingsItem
*
settingsItem
=
_addMissionSettings
(
visualItems
);
if
(
json
.
contains
(
_jsonPlannedHomePositionKey
))
{
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
visualItems
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
true
/* forLoad */
,
visualItems
);
if
(
item
->
load
(
json
[
_jsonPlannedHomePositionKey
].
toObject
(),
0
,
errorString
))
{
settingsItem
->
setInitialHomePositionFromUser
(
item
->
coordinate
());
item
->
deleteLater
();
...
...
@@ -687,11 +691,11 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
const
QJsonObject
itemObject
=
itemValue
.
toObject
();
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
visualItems
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
true
/* forLoad */
,
visualItems
);
if
(
item
->
load
(
itemObject
,
itemObject
[
"id"
].
toInt
(),
errorString
))
{
if
(
TakeoffMissionItem
::
isTakeoffCommand
(
item
->
mavCommand
()))
{
// This needs to be a TakeoffMissionItem
TakeoffMissionItem
*
takeoffItem
=
new
TakeoffMissionItem
(
_masterController
,
_flyView
,
settingsItem
,
visualItems
);
TakeoffMissionItem
*
takeoffItem
=
new
TakeoffMissionItem
(
_masterController
,
_flyView
,
settingsItem
,
true
/* forLoad */
,
visualItems
);
takeoffItem
->
load
(
itemObject
,
itemObject
[
"id"
].
toInt
(),
errorString
);
item
->
deleteLater
();
item
=
takeoffItem
;
...
...
@@ -775,11 +779,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
QString
itemType
=
itemObject
[
VisualMissionItem
::
jsonTypeKey
].
toString
();
if
(
itemType
==
VisualMissionItem
::
jsonTypeSimpleItemValue
)
{
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
visualItems
);
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
true
/* forLoad */
,
visualItems
);
if
(
simpleItem
->
load
(
itemObject
,
nextSequenceNumber
,
errorString
))
{
if
(
TakeoffMissionItem
::
isTakeoffCommand
(
static_cast
<
MAV_CMD
>
(
simpleItem
->
command
())))
{
// This needs to be a TakeoffMissionItem
TakeoffMissionItem
*
takeoffItem
=
new
TakeoffMissionItem
(
_masterController
,
_flyView
,
settingsItem
,
this
);
TakeoffMissionItem
*
takeoffItem
=
new
TakeoffMissionItem
(
_masterController
,
_flyView
,
settingsItem
,
t
rue
/* forLoad */
,
t
his
);
takeoffItem
->
load
(
itemObject
,
nextSequenceNumber
,
errorString
);
simpleItem
->
deleteLater
();
simpleItem
=
takeoffItem
;
...
...
@@ -919,14 +923,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
MissionSettingsItem
*
settingsItem
=
_addMissionSettings
(
visualItems
);
while
(
!
stream
.
atEnd
())
{
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
visualItems
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_masterController
,
_flyView
,
true
/* forLoad */
,
visualItems
);
if
(
item
->
load
(
stream
))
{
if
(
firstItem
&&
plannedHomePositionInFile
)
{
settingsItem
->
setInitialHomePositionFromUser
(
item
->
coordinate
());
}
else
{
if
(
TakeoffMissionItem
::
isTakeoffCommand
(
static_cast
<
MAV_CMD
>
(
item
->
command
())))
{
// This needs to be a TakeoffMissionItem
TakeoffMissionItem
*
takeoffItem
=
new
TakeoffMissionItem
(
_masterController
,
_flyView
,
settingsItem
,
visualItems
);
TakeoffMissionItem
*
takeoffItem
=
new
TakeoffMissionItem
(
_masterController
,
_flyView
,
settingsItem
,
true
/* forLoad */
,
visualItems
);
takeoffItem
->
load
(
stream
);
item
->
deleteLater
();
item
=
takeoffItem
;
...
...
@@ -2283,6 +2287,7 @@ void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
_currentPlanViewItem
=
nullptr
;
_currentPlanViewSeqNum
=
-
1
;
_currentPlanViewVIIndex
=
-
1
;
_onlyInsertTakeoffValid
=
!
_planViewSettings
->
takeoffItemNotRequired
()
->
rawValue
().
toBool
()
&&
_visualItems
->
count
()
==
1
;
// First item must be takeoff
_isInsertTakeoffValid
=
true
;
_isInsertLandValid
=
true
;
_isROIActive
=
false
;
...
...
@@ -2412,10 +2417,15 @@ void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
}
}
// These are not valid when only takeoff is allowed
_isInsertLandValid
=
_isInsertLandValid
&&
!
_onlyInsertTakeoffValid
;
_flyThroughCommandsAllowed
=
_flyThroughCommandsAllowed
&&
!
_onlyInsertTakeoffValid
;
emit
currentPlanViewSeqNumChanged
();
emit
currentPlanViewVIIndexChanged
();
emit
currentPlanViewItemChanged
();
emit
splitSegmentChanged
();
emit
onlyInsertTakeoffValidChanged
();
emit
isInsertTakeoffValidChanged
();
emit
isInsertLandValidChanged
();
emit
isROIActiveChanged
();
...
...
@@ -2513,3 +2523,9 @@ bool MissionController::isEmpty(void) const
{
return
_visualItems
->
count
()
<=
1
;
}
void
MissionController
::
_takeoffItemNotRequiredChanged
(
void
)
{
// Force a recalc of allowed bits
setCurrentPlanViewSeqNum
(
_currentPlanViewSeqNum
,
true
/* force */
);
}
src/MissionManager/MissionController.h
View file @
02925e1e
...
...
@@ -28,6 +28,7 @@ class SimpleMissionItem;
class
ComplexMissionItem
;
class
MissionSettingsItem
;
class
QDomDocument
;
class
PlanViewSettings
;
Q_DECLARE_LOGGING_CATEGORY
(
MissionControllerLog
)
...
...
@@ -95,6 +96,7 @@ public:
Q_PROPERTY
(
QString
surveyComplexItemName
READ
surveyComplexItemName
CONSTANT
)
Q_PROPERTY
(
QString
corridorScanComplexItemName
READ
corridorScanComplexItemName
CONSTANT
)
Q_PROPERTY
(
QString
structureScanComplexItemName
READ
structureScanComplexItemName
CONSTANT
)
Q_PROPERTY
(
bool
onlyInsertTakeoffValid
MEMBER
_onlyInsertTakeoffValid
NOTIFY
onlyInsertTakeoffValidChanged
)
Q_PROPERTY
(
bool
isInsertTakeoffValid
MEMBER
_isInsertTakeoffValid
NOTIFY
isInsertTakeoffValidChanged
)
Q_PROPERTY
(
bool
isInsertLandValid
MEMBER
_isInsertLandValid
NOTIFY
isInsertLandValidChanged
)
Q_PROPERTY
(
bool
isROIActive
MEMBER
_isROIActive
NOTIFY
isROIActiveChanged
)
...
...
@@ -263,6 +265,7 @@ signals:
void
currentPlanViewItemChanged
(
void
);
void
missionBoundingCubeChanged
(
void
);
void
missionItemCountChanged
(
int
missionItemCount
);
void
onlyInsertTakeoffValidChanged
(
void
);
void
isInsertTakeoffValidChanged
(
void
);
void
isInsertLandValidChanged
(
void
);
void
isROIActiveChanged
(
void
);
...
...
@@ -286,6 +289,7 @@ private slots:
void
_complexBoundingBoxChanged
(
void
);
void
_recalcAll
(
void
);
void
_managerVehicleChanged
(
Vehicle
*
managerVehicle
);
void
_takeoffItemNotRequiredChanged
(
void
);
private:
void
_init
(
void
);
...
...
@@ -334,6 +338,7 @@ private:
int
_missionItemCount
=
0
;
QmlObjectListModel
*
_visualItems
=
nullptr
;
MissionSettingsItem
*
_settingsItem
=
nullptr
;
PlanViewSettings
*
_planViewSettings
=
nullptr
;
QmlObjectListModel
_waypointLines
;
QVariantList
_waypointPath
;
QmlObjectListModel
_directionArrows
;
...
...
@@ -353,10 +358,11 @@ private:
QGeoCoordinate
_takeoffCoordinate
;
QGeoCoordinate
_previousCoordinate
;
CoordinateVector
*
_splitSegment
=
nullptr
;
bool
_onlyInsertTakeoffValid
=
true
;
bool
_isInsertTakeoffValid
=
true
;
bool
_isInsertLandValid
=
tru
e
;
bool
_isInsertLandValid
=
fals
e
;
bool
_isROIActive
=
false
;
bool
_flyThroughCommandsAllowed
=
tru
e
;
bool
_flyThroughCommandsAllowed
=
fals
e
;
bool
_isROIBeginCurrentItem
=
false
;
static
const
char
*
_settingsGroup
;
...
...
src/MissionManager/MissionItemTest.cc
View file @
02925e1e
...
...
@@ -278,7 +278,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem
simpleMissionItem
(
_masterController
,
false
/* flyView */
,
nullptr
);
SimpleMissionItem
simpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
nullptr
);
QString
testString
(
"10
\t
0
\t
3
\t
80
\t
10
\t
20
\t
30
\t
40
\t
-10
\t
-20
\t
-30
\t
1
\r\n
"
);
QTextStream
testStream
(
&
testString
,
QIODevice
::
ReadOnly
);
...
...
@@ -448,7 +448,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem
simpleMissionItem
(
_masterController
,
false
/* flyView */
,
nullptr
);
SimpleMissionItem
simpleMissionItem
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
nullptr
);
QString
errorString
;
QJsonArray
coordinateArray
;
QJsonObject
jsonObject
;
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
02925e1e
...
...
@@ -52,7 +52,7 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = {
{
"MAV_FRAME_GLOBAL_TERRAIN_ALT_INT"
,
MAV_FRAME_GLOBAL_TERRAIN_ALT_INT
},
};
SimpleMissionItem
::
SimpleMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
QObject
*
parent
)
SimpleMissionItem
::
SimpleMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
bool
forLoad
,
QObject
*
parent
)
:
VisualMissionItem
(
masterController
,
flyView
,
parent
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_supportedCommandFact
(
0
,
"Command:"
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -69,13 +69,15 @@ SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, boo
_editorQml
=
QStringLiteral
(
"qrc:/qml/SimpleItemEditor.qml"
);
_setupMetaData
();
_connectSignals
();
_updateOptionalSections
();
_setDefaultsForCommand
();
_rebuildFacts
();
setDirty
(
false
);
if
(
!
forLoad
)
{
// We are are going to load the SimpleItem right after this then don't connnect up signalling until after load is done
_connectSignals
();
_updateOptionalSections
();
_setDefaultsForCommand
();
_rebuildFacts
();
setDirty
(
false
);
}
}
SimpleMissionItem
::
SimpleMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
const
MissionItem
&
missionItem
,
QObject
*
parent
)
...
...
@@ -280,7 +282,10 @@ bool SimpleMissionItem::load(QTextStream &loadStream)
_altitudeFact
.
setRawValue
(
_missionItem
.
_param7Fact
.
rawValue
());
_amslAltAboveTerrainFact
.
setRawValue
(
qQNaN
());
}
_connectSignals
();
_updateOptionalSections
();
_rebuildFacts
();
setDirty
(
false
);
}
return
success
;
...
...
@@ -313,7 +318,10 @@ bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QStrin
}
}
_connectSignals
();
_updateOptionalSections
();
_rebuildFacts
();
setDirty
(
false
);
return
true
;
}
...
...
src/MissionManager/SimpleMissionItem.h
View file @
02925e1e
...
...
@@ -24,9 +24,8 @@ class SimpleMissionItem : public VisualMissionItem
Q_OBJECT
public:
SimpleMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
QObject
*
parent
);
SimpleMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
bool
forLoad
,
QObject
*
parent
);
SimpleMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
const
MissionItem
&
missionItem
,
QObject
*
parent
);
//SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent);
~
SimpleMissionItem
();
...
...
src/MissionManager/SimpleMissionItemTest.cc
View file @
02925e1e
...
...
@@ -166,7 +166,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
void
SimpleMissionItemTest
::
_testDefaultValues
(
void
)
{
SimpleMissionItem
item
(
_masterController
,
false
/* flyView */
,
nullptr
);
SimpleMissionItem
item
(
_masterController
,
false
/* flyView */
,
false
/* forLoad */
,
nullptr
);
item
.
missionItem
().
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
item
.
missionItem
().
setFrame
(
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
...
...
src/MissionManager/SurveyComplexItem.cc
View file @
02925e1e
...
...
@@ -79,6 +79,11 @@ SurveyComplexItem::SurveyComplexItem(PlanMasterController* masterController, boo
_turnAroundDistanceFact
.
setRawValue
(
10
);
}
if
(
_controllerVehicle
&&
!
(
_controllerVehicle
->
fixedWing
()
||
_controllerVehicle
->
vtol
()))
{
// Only fixed wing flight paths support alternate transects
_flyAlternateTransectsFact
.
setRawValue
(
false
);
}
// We override the altitude to the mission default
if
(
_cameraCalc
.
isManualCamera
()
||
!
_cameraCalc
.
valueSetIsDistance
()
->
rawValue
().
toBool
())
{
_cameraCalc
.
distanceToSurface
()
->
setRawValue
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
defaultMissionItemAltitude
()
->
rawValue
());
...
...
src/MissionManager/TakeoffMissionItem.cc
View file @
02925e1e
...
...
@@ -20,26 +20,27 @@
#include "SettingsManager.h"
#include "PlanMasterController.h"
TakeoffMissionItem
::
TakeoffMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
QObject
*
parent
)
:
SimpleMissionItem
(
masterController
,
flyView
,
parent
)
TakeoffMissionItem
::
TakeoffMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
bool
forLoad
,
QObject
*
parent
)
:
SimpleMissionItem
(
masterController
,
flyView
,
forLoad
,
parent
)
,
_settingsItem
(
settingsItem
)
{
_init
();
_init
(
forLoad
);
}
TakeoffMissionItem
::
TakeoffMissionItem
(
MAV_CMD
takeoffCmd
,
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
QObject
*
parent
)
:
SimpleMissionItem
(
masterController
,
flyView
,
parent
)
:
SimpleMissionItem
(
masterController
,
flyView
,
false
/* forLoad */
,
parent
)
,
_settingsItem
(
settingsItem
)
{
setCommand
(
takeoffCmd
);
_init
();
_init
(
false
/* forLoad */
);
}
TakeoffMissionItem
::
TakeoffMissionItem
(
const
MissionItem
&
missionItem
,
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
QObject
*
parent
)
:
SimpleMissionItem
(
masterController
,
flyView
,
missionItem
,
parent
)
,
_settingsItem
(
settingsItem
)
{
_init
();
_init
(
false
/* forLoad */
);
_wizardMode
=
false
;
}
TakeoffMissionItem
::~
TakeoffMissionItem
()
...
...
@@ -47,7 +48,7 @@ TakeoffMissionItem::~TakeoffMissionItem()
}
void
TakeoffMissionItem
::
_init
(
voi
d
)
void
TakeoffMissionItem
::
_init
(
bool
forLoa
d
)
{
_editorQml
=
QStringLiteral
(
"qrc:/qml/SimpleItemEditor.qml"
);
...
...
@@ -69,10 +70,15 @@ void TakeoffMissionItem::_init(void)
}
}
if
(
forLoad
)
{
// Load routines will set the rest up after load
return
;
}
_initLaunchTakeoffAtSameLocation
();
if
(
homePosition
.
isValid
()
&&
coordinate
().
isValid
())
{
// Item already full specified, most likely from mission load from storage
// Item already full
y
specified, most likely from mission load from storage
_wizardMode
=
false
;
}
else
{
if
(
_launchTakeoffAtSameLocation
&&
homePosition
.
isValid
())
{
...
...
@@ -140,6 +146,7 @@ bool TakeoffMissionItem::load(QTextStream &loadStream)
if
(
success
)
{
_initLaunchTakeoffAtSameLocation
();
}
_wizardMode
=
false
;
// Always be off for loaded items
return
success
;
}
...
...
@@ -149,6 +156,7 @@ bool TakeoffMissionItem::load(const QJsonObject& json, int sequenceNumber, QStri
if
(
success
)
{
_initLaunchTakeoffAtSameLocation
();
}
_wizardMode
=
false
;
// Always be off for loaded items
return
success
;
}
...
...
src/MissionManager/TakeoffMissionItem.h
View file @
02925e1e
...
...
@@ -21,7 +21,7 @@ class TakeoffMissionItem : public SimpleMissionItem
Q_OBJECT
public:
TakeoffMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
QObject
*
parent
);
TakeoffMissionItem
(
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
bool
forLoad
,
QObject
*
parent
);
TakeoffMissionItem
(
MAV_CMD
takeoffCmd
,
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
QObject
*
parent
);
TakeoffMissionItem
(
const
MissionItem
&
missionItem
,
PlanMasterController
*
masterController
,
bool
flyView
,
MissionSettingsItem
*
settingsItem
,
QObject
*
parent
);
...
...
@@ -57,7 +57,7 @@ signals:
void
launchTakeoffAtSameLocationChanged
(
bool
launchTakeoffAtSameLocation
);
private:
void
_init
(
voi
d
);
void
_init
(
bool
forLoa
d
);
void
_initLaunchTakeoffAtSameLocation
(
void
);
MissionSettingsItem
*
_settingsItem
;
...
...
src/MissionManager/TransectStyleComplexItem.cc
View file @
02925e1e
...
...
@@ -498,7 +498,19 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te
TransectStyleComplexItem
::
ReadyForSaveState
TransectStyleComplexItem
::
readyForSaveState
(
void
)
const
{
bool
terrainReady
=
_followTerrain
?
_transectsPathHeightInfo
.
count
()
:
true
;
bool
terrainReady
=
false
;
if
(
_followTerrain
)
{
if
(
_loadedMissionItems
.
count
())
{
// We have loaded mission items. Everything is ready to go.
terrainReady
=
true
;
}
else
{
// Survey is currently being designed. We aren't ready if we don't have terrain heights yet.
terrainReady
=
_transectsPathHeightInfo
.
count
();
}
}
else
{
// Now following terrain so always ready on terrain
terrainReady
=
true
;
}
bool
polygonNotReady
=
!
_surveyAreaPolygon
.
isValid
();
return
(
polygonNotReady
||
_wizardMode
)
?
NotReadyForSaveData
:
...
...
src/MissionManager/UnitTest/MP 19.prj
0 → 100644
View file @
02925e1e
GEOGCS["GCS_WGS_1984",DATUM["D_WGS_1984",SPHEROID["WGS_1984",6378137,298.257223563]],PRIMEM["Greenwich",0],UNIT["Degree",0.017453292519943295]]
\ No newline at end of file
src/MissionManager/UnitTest/MP 19.shp
0 → 100644
View file @
02925e1e
File added
src/MissionManager/UnitTest/MP 19.shx
0 → 100644
View file @
02925e1e
File added
src/MissionManager/UnitTest/MP Bonus.prj
0 → 100644
View file @
02925e1e
GEOGCS["GCS_WGS_1984",DATUM["D_WGS_1984",SPHEROID["WGS_1984",6378137,298.257223563]],PRIMEM["Greenwich",0],UNIT["Degree",0.017453292519943295]]
\ No newline at end of file
src/MissionManager/UnitTest/MP Bonus.shp
0 → 100644
View file @
02925e1e
File added
src/MissionManager/UnitTest/MP Bonus.shx
0 → 100644
View file @
02925e1e
File added
src/MissionManager/UnitTest/Sarah's Farm.prj
0 → 100644
View file @
02925e1e
GEOGCS["GCS_WGS_1984",DATUM["D_WGS_1984",SPHEROID["WGS_1984",6378137,298.257223563]],PRIMEM["Greenwich",0],UNIT["Degree",0.017453292519943295]]
\ No newline at end of file
src/MissionManager/UnitTest/Sarah's Farm.shp
0 → 100644
View file @
02925e1e
File added
src/MissionManager/UnitTest/Sarah's Farm.shx
0 → 100644
View file @
02925e1e
File added
src/PlanView/PlanView.qml
View file @
02925e1e
...
...
@@ -617,7 +617,7 @@ Item {
{
name
:
_missionController
.
isROIActive
?
qsTr
(
"
Cancel ROI
"
)
:
qsTr
(
"
ROI
"
),
iconSource
:
"
/qmlimages/MapAddMission.svg
"
,
buttonEnabled
:
true
,
buttonEnabled
:
!
_missionController
.
onlyInsertTakeoffValid
,
buttonVisible
:
_isMissionLayer
&&
_planMasterController
.
controllerVehicle
.
roiModeSupported
,
toggle
:
!
_missionController
.
isROIActive
},
...
...
src/QmlControls/QGCFileDialog.qml
View file @
02925e1e
...
...
@@ -117,12 +117,12 @@ Item {
onClicked
:
{
hideDialog
()
_root
.
acceptedForLoad
(
controller
.
fullyQualifiedFilename
(
folder
,
modelData
,
fileExtension
))
_root
.
acceptedForLoad
(
controller
.
fullyQualifiedFilename
(
folder
,
modelData
,
_rgExtensions
))
}
onHamburgerClicked
:
{
highlight
=
true
hamburgerMenu
.
fileToDelete
=
controller
.
fullyQualifiedFilename
(
folder
,
modelData
,
fileExtension
)
hamburgerMenu
.
fileToDelete
=
controller
.
fullyQualifiedFilename
(
folder
,
modelData
,
_rgExtensions
)
hamburgerMenu
.
popup
()
}
...
...
@@ -162,12 +162,12 @@ Item {
return
}
if
(
!
replaceMessage
.
visible
)
{