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
c7a171eb
Unverified
Commit
c7a171eb
authored
Aug 21, 2018
by
Gus Grubba
Committed by
GitHub
Aug 21, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6817 from mavlink/customPlan
Custom Plan Save/Load
parents
44f8b922
1d239f92
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
112 additions
and
81 deletions
+112
-81
MissionController.cc
src/MissionManager/MissionController.cc
+22
-22
PlanMasterController.cc
src/MissionManager/PlanMasterController.cc
+34
-19
PlanMasterController.h
src/MissionManager/PlanMasterController.h
+6
-5
QGCCorePlugin.cc
src/api/QGCCorePlugin.cc
+34
-34
QGCCorePlugin.h
src/api/QGCCorePlugin.h
+16
-1
No files found.
src/MissionManager/MissionController.cc
View file @
c7a171eb
...
...
@@ -56,8 +56,8 @@ const int MissionController::_missionFileVersion = 2;
MissionController
::
MissionController
(
PlanMasterController
*
masterController
,
QObject
*
parent
)
:
PlanElementController
(
masterController
,
parent
)
,
_missionManager
(
_managerVehicle
->
missionManager
())
,
_visualItems
(
NULL
)
,
_settingsItem
(
NULL
)
,
_visualItems
(
nullptr
)
,
_settingsItem
(
nullptr
)
,
_firstItemsFromVehicle
(
false
)
,
_itemsRequested
(
false
)
,
_inRecalcSequence
(
false
)
...
...
@@ -68,7 +68,7 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
,
_appSettings
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
())
,
_progressPct
(
0
)
,
_currentPlanViewIndex
(
-
1
)
,
_currentPlanViewItem
(
NULL
)
,
_currentPlanViewItem
(
nullptr
)
{
_resetMissionFlightStatus
();
managerVehicleChanged
(
_managerVehicle
);
...
...
@@ -109,7 +109,7 @@ void MissionController::_resetMissionFlightStatus(void)
_controllerVehicle
->
firmwarePlugin
()
->
batteryConsumptionData
(
_controllerVehicle
,
_missionFlightStatus
.
mAhBattery
,
_missionFlightStatus
.
hoverAmps
,
_missionFlightStatus
.
cruiseAmps
);
if
(
_missionFlightStatus
.
mAhBattery
!=
0
)
{
double
batteryPercentRemainingAnnounce
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
batteryPercentRemainingAnnounce
()
->
rawValue
().
toDouble
();
_missionFlightStatus
.
ampMinutesAvailable
=
(
double
)
_missionFlightStatus
.
mAhBattery
/
1000.0
*
60.0
*
((
100.0
-
batteryPercentRemainingAnnounce
)
/
100.0
);
_missionFlightStatus
.
ampMinutesAvailable
=
static_cast
<
double
>
(
_missionFlightStatus
.
mAhBattery
)
/
1000.0
*
60.0
*
((
100.0
-
batteryPercentRemainingAnnounce
)
/
100.0
);
}
emit
missionDistanceChanged
(
_missionFlightStatus
.
totalDistance
);
...
...
@@ -182,8 +182,8 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
_deinitAllVisualItems
();
_visualItems
->
deleteLater
();
_settingsItem
=
NULL
;
_visualItems
=
NULL
;
_settingsItem
=
nullptr
;
_visualItems
=
nullptr
;
_updateContainsItems
();
// This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
_visualItems
=
newControllerMissionItems
;
...
...
@@ -351,7 +351,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
_initVisualItem
(
newItem
);
if
(
_visualItems
->
count
()
==
1
&&
(
_controllerVehicle
->
fixedWing
()
||
_controllerVehicle
->
vtol
()
||
_controllerVehicle
->
multiRotor
()))
{
MAV_CMD
takeoffCmd
=
_controllerVehicle
->
vtol
()
?
MAV_CMD_NAV_VTOL_TAKEOFF
:
MAV_CMD_NAV_TAKEOFF
;
if
(
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
(
MAV_CMD
)
takeoffCmd
))
{
if
(
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
takeoffCmd
))
{
newItem
->
setCommand
(
takeoffCmd
);
}
}
...
...
@@ -361,7 +361,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
if
(
_findPreviousAltitude
(
i
,
&
prevAltitude
,
&
prevAltitudeMode
))
{
newItem
->
altitude
()
->
setRawValue
(
prevAltitude
);
newItem
->
setAltitudeMode
(
(
SimpleMissionItem
::
AltitudeMode
)
prevAltitudeMode
);
newItem
->
setAltitudeMode
(
static_cast
<
SimpleMissionItem
::
AltitudeMode
>
(
prevAltitudeMode
)
);
}
}
newItem
->
setMissionFlightStatus
(
_missionFlightStatus
);
...
...
@@ -377,7 +377,7 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
int
sequenceNumber
=
_nextSequenceNumber
();
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
_controllerVehicle
,
_flyView
,
this
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
newItem
->
setCommand
((
MAV_CMD
)(
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
((
MAV_CMD
)
MAV_CMD_DO_SET_ROI_LOCATION
)
?
newItem
->
setCommand
((
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
MAV_CMD_DO_SET_ROI_LOCATION
)
?
MAV_CMD_DO_SET_ROI_LOCATION
:
MAV_CMD_DO_SET_ROI
));
_initVisualItem
(
newItem
);
...
...
@@ -388,7 +388,7 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
if
(
_findPreviousAltitude
(
i
,
&
prevAltitude
,
&
prevAltitudeMode
))
{
newItem
->
altitude
()
->
setRawValue
(
prevAltitude
);
newItem
->
setAltitudeMode
(
(
SimpleMissionItem
::
AltitudeMode
)
prevAltitudeMode
);
newItem
->
setAltitudeMode
(
static_cast
<
SimpleMissionItem
::
AltitudeMode
>
(
prevAltitudeMode
)
);
}
_visualItems
->
insert
(
i
,
newItem
);
...
...
@@ -533,7 +533,7 @@ void MissionController::removeAll(void)
_deinitAllVisualItems
();
_visualItems
->
clearAndDeleteContents
();
_visualItems
->
deleteLater
();
_settingsItem
=
NULL
;
_settingsItem
=
nullptr
;
_visualItems
=
new
QmlObjectListModel
(
this
);
_addMissionSettings
(
_visualItems
,
false
/* addToCenter */
);
_initAllVisualItems
();
...
...
@@ -661,9 +661,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if
(
_masterController
->
offline
())
{
// We only update if offline since if we are online we use the online vehicle settings
appSettings
->
offlineEditingFirmwareType
()
->
setRawValue
(
AppSettings
::
offlineEditingFirmwareTypeFromFirmwareType
(
(
MAV_AUTOPILOT
)
json
[
_jsonFirmwareTypeKey
].
toInt
(
)));
appSettings
->
offlineEditingFirmwareType
()
->
setRawValue
(
AppSettings
::
offlineEditingFirmwareTypeFromFirmwareType
(
static_cast
<
MAV_AUTOPILOT
>
(
json
[
_jsonFirmwareTypeKey
].
toInt
()
)));
if
(
json
.
contains
(
_jsonVehicleTypeKey
))
{
appSettings
->
offlineEditingVehicleType
()
->
setRawValue
(
AppSettings
::
offlineEditingVehicleTypeFromVehicleType
(
(
MAV_TYPE
)
json
[
_jsonVehicleTypeKey
].
toInt
(
)));
appSettings
->
offlineEditingVehicleType
()
->
setRawValue
(
AppSettings
::
offlineEditingVehicleTypeFromVehicleType
(
static_cast
<
MAV_TYPE
>
(
json
[
_jsonVehicleTypeKey
].
toInt
()
)));
}
}
if
(
json
.
contains
(
_jsonCruiseSpeedKey
))
{
...
...
@@ -781,9 +781,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
for
(
int
i
=
0
;
i
<
visualItems
->
count
();
i
++
)
{
if
(
visualItems
->
value
<
VisualMissionItem
*>
(
i
)
->
isSimpleItem
())
{
SimpleMissionItem
*
doJumpItem
=
visualItems
->
value
<
SimpleMissionItem
*>
(
i
);
if
(
(
MAV_CMD
)
doJumpItem
->
command
()
==
MAV_CMD_DO_JUMP
)
{
if
(
doJumpItem
->
command
()
==
MAV_CMD_DO_JUMP
)
{
bool
found
=
false
;
int
findDoJumpId
=
doJumpItem
->
missionItem
().
param1
(
);
int
findDoJumpId
=
static_cast
<
int
>
(
doJumpItem
->
missionItem
().
param1
()
);
for
(
int
j
=
0
;
j
<
visualItems
->
count
();
j
++
)
{
if
(
visualItems
->
value
<
VisualMissionItem
*>
(
j
)
->
isSimpleItem
())
{
SimpleMissionItem
*
targetItem
=
visualItems
->
value
<
SimpleMissionItem
*>
(
j
);
...
...
@@ -878,7 +878,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
for
(
int
i
=
1
;
i
<
visualItems
->
count
();
i
++
)
{
SimpleMissionItem
*
item
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItems
->
get
(
i
));
if
(
item
&&
item
->
command
()
==
MAV_CMD_DO_JUMP
)
{
item
->
missionItem
().
setParam1
(
(
int
)
item
->
missionItem
().
param1
(
)
+
1
);
item
->
missionItem
().
setParam1
(
static_cast
<
int
>
(
item
->
missionItem
().
param1
()
)
+
1
);
}
}
}
...
...
@@ -891,7 +891,7 @@ void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualI
if
(
_visualItems
)
{
_deinitAllVisualItems
();
_visualItems
->
deleteLater
();
_settingsItem
=
NULL
;
_settingsItem
=
nullptr
;
}
_visualItems
=
loadedVisualItems
;
...
...
@@ -987,11 +987,11 @@ void MissionController::save(QJsonObject& json)
}
QJsonValue
coordinateValue
;
JsonHelper
::
saveGeoCoordinate
(
settingsItem
->
coordinate
(),
true
/* writeAltitude */
,
coordinateValue
);
json
[
_jsonPlannedHomePositionKey
]
=
coordinateValue
;
json
[
_jsonFirmwareTypeKey
]
=
_controllerVehicle
->
firmwareType
();
json
[
_jsonVehicleTypeKey
]
=
_controllerVehicle
->
vehicleType
();
json
[
_jsonCruiseSpeedKey
]
=
_controllerVehicle
->
defaultCruiseSpeed
();
json
[
_jsonHoverSpeedKey
]
=
_controllerVehicle
->
defaultHoverSpeed
();
json
[
_jsonPlannedHomePositionKey
]
=
coordinateValue
;
json
[
_jsonFirmwareTypeKey
]
=
_controllerVehicle
->
firmwareType
();
json
[
_jsonVehicleTypeKey
]
=
_controllerVehicle
->
vehicleType
();
json
[
_jsonCruiseSpeedKey
]
=
_controllerVehicle
->
defaultCruiseSpeed
();
json
[
_jsonHoverSpeedKey
]
=
_controllerVehicle
->
defaultHoverSpeed
();
// Save the visual items
...
...
src/MissionManager/PlanMasterController.cc
View file @
c7a171eb
...
...
@@ -9,6 +9,7 @@
#include "PlanMasterController.h"
#include "QGCApplication.h"
#include "QGCCorePlugin.h"
#include "MultiVehicleManager.h"
#include "SettingsManager.h"
#include "AppSettings.h"
...
...
@@ -22,16 +23,19 @@
QGC_LOGGING_CATEGORY
(
PlanMasterControllerLog
,
"PlanMasterControllerLog"
)
const
int
PlanMasterController
::
_p
lanFileVersion
=
1
;
const
char
*
PlanMasterController
::
_p
lanFileType
=
"Plan"
;
const
char
*
PlanMasterController
::
_j
sonMissionObjectKey
=
"mission"
;
const
char
*
PlanMasterController
::
_j
sonGeoFenceObjectKey
=
"geoFence"
;
const
char
*
PlanMasterController
::
_j
sonRallyPointsObjectKey
=
"rallyPoints"
;
const
int
PlanMasterController
::
kP
lanFileVersion
=
1
;
const
char
*
PlanMasterController
::
kP
lanFileType
=
"Plan"
;
const
char
*
PlanMasterController
::
kJ
sonMissionObjectKey
=
"mission"
;
const
char
*
PlanMasterController
::
kJ
sonGeoFenceObjectKey
=
"geoFence"
;
const
char
*
PlanMasterController
::
kJ
sonRallyPointsObjectKey
=
"rallyPoints"
;
PlanMasterController
::
PlanMasterController
(
QObject
*
parent
)
:
QObject
(
parent
)
,
_multiVehicleMgr
(
qgcApp
()
->
toolbox
()
->
multiVehicleManager
())
,
_controllerVehicle
(
new
Vehicle
((
MAV_AUTOPILOT
)
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
offlineEditingFirmwareType
()
->
rawValue
().
toInt
(),
(
MAV_TYPE
)
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
offlineEditingVehicleType
()
->
rawValue
().
toInt
(),
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
()))
,
_controllerVehicle
(
new
Vehicle
(
static_cast
<
MAV_AUTOPILOT
>
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
offlineEditingFirmwareType
()
->
rawValue
().
toInt
()),
static_cast
<
MAV_TYPE
>
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
offlineEditingVehicleType
()
->
rawValue
().
toInt
()),
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
()))
,
_managerVehicle
(
_controllerVehicle
)
,
_flyView
(
true
)
,
_offline
(
true
)
...
...
@@ -101,7 +105,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
}
bool
newOffline
=
false
;
if
(
activeVehicle
==
NULL
)
{
if
(
activeVehicle
==
nullptr
)
{
// Since there is no longer an active vehicle we use the offline controller vehicle as the manager vehicle
_managerVehicle
=
_controllerVehicle
;
newOffline
=
true
;
...
...
@@ -299,28 +303,33 @@ void PlanMasterController::loadFromFile(const QString& filename)
return
;
}
int
version
;
QJsonObject
json
=
jsonDoc
.
object
();
if
(
!
JsonHelper
::
validateQGCJsonFile
(
json
,
_planFileType
,
_planFileVersion
,
_planFileVersion
,
version
,
errorString
))
{
//-- Allow plugins to pre process the load
qgcApp
()
->
toolbox
()
->
corePlugin
()
->
preLoadFromJson
(
this
,
json
);
int
version
;
if
(
!
JsonHelper
::
validateQGCJsonFile
(
json
,
kPlanFileType
,
kPlanFileVersion
,
kPlanFileVersion
,
version
,
errorString
))
{
qgcApp
()
->
showMessage
(
errorMessage
.
arg
(
errorString
));
return
;
}
QList
<
JsonHelper
::
KeyValidateInfo
>
rgKeyInfo
=
{
{
_j
sonMissionObjectKey
,
QJsonValue
::
Object
,
true
},
{
_j
sonGeoFenceObjectKey
,
QJsonValue
::
Object
,
true
},
{
_j
sonRallyPointsObjectKey
,
QJsonValue
::
Object
,
true
},
{
kJ
sonMissionObjectKey
,
QJsonValue
::
Object
,
true
},
{
kJ
sonGeoFenceObjectKey
,
QJsonValue
::
Object
,
true
},
{
kJ
sonRallyPointsObjectKey
,
QJsonValue
::
Object
,
true
},
};
if
(
!
JsonHelper
::
validateKeys
(
json
,
rgKeyInfo
,
errorString
))
{
qgcApp
()
->
showMessage
(
errorMessage
.
arg
(
errorString
));
return
;
}
if
(
!
_missionController
.
load
(
json
[
_j
sonMissionObjectKey
].
toObject
(),
errorString
)
||
!
_geoFenceController
.
load
(
json
[
_j
sonGeoFenceObjectKey
].
toObject
(),
errorString
)
||
!
_rallyPointController
.
load
(
json
[
_j
sonRallyPointsObjectKey
].
toObject
(),
errorString
))
{
if
(
!
_missionController
.
load
(
json
[
kJ
sonMissionObjectKey
].
toObject
(),
errorString
)
||
!
_geoFenceController
.
load
(
json
[
kJ
sonGeoFenceObjectKey
].
toObject
(),
errorString
)
||
!
_rallyPointController
.
load
(
json
[
kJ
sonRallyPointsObjectKey
].
toObject
(),
errorString
))
{
qgcApp
()
->
showMessage
(
errorMessage
.
arg
(
errorString
));
}
else
{
//-- Allow plugins to post process the load
qgcApp
()
->
toolbox
()
->
corePlugin
()
->
postLoadFromJson
(
this
,
json
);
success
=
true
;
}
}
else
if
(
fileInfo
.
suffix
()
==
AppSettings
::
missionFileExtension
)
{
...
...
@@ -354,16 +363,22 @@ void PlanMasterController::loadFromFile(const QString& filename)
QJsonDocument
PlanMasterController
::
saveToJson
()
{
QJsonObject
planJson
;
qgcApp
()
->
toolbox
()
->
corePlugin
()
->
preSaveToJson
(
this
,
planJson
);
QJsonObject
missionJson
;
QJsonObject
fenceJson
;
QJsonObject
rallyJson
;
JsonHelper
::
saveQGCJsonFileHeader
(
planJson
,
_planFileType
,
_planFileVersion
);
JsonHelper
::
saveQGCJsonFileHeader
(
planJson
,
kPlanFileType
,
kPlanFileVersion
);
//-- Allow plugin to preemptly add its own keys to mission
qgcApp
()
->
toolbox
()
->
corePlugin
()
->
preSaveToMissionJson
(
this
,
missionJson
);
_missionController
.
save
(
missionJson
);
//-- Allow plugin to add its own keys to mission
qgcApp
()
->
toolbox
()
->
corePlugin
()
->
postSaveToMissionJson
(
this
,
missionJson
);
_geoFenceController
.
save
(
fenceJson
);
_rallyPointController
.
save
(
rallyJson
);
planJson
[
_jsonMissionObjectKey
]
=
missionJson
;
planJson
[
_jsonGeoFenceObjectKey
]
=
fenceJson
;
planJson
[
_jsonRallyPointsObjectKey
]
=
rallyJson
;
planJson
[
kJsonMissionObjectKey
]
=
missionJson
;
planJson
[
kJsonGeoFenceObjectKey
]
=
fenceJson
;
planJson
[
kJsonRallyPointsObjectKey
]
=
rallyJson
;
qgcApp
()
->
toolbox
()
->
corePlugin
()
->
postSaveToJson
(
this
,
planJson
);
return
QJsonDocument
(
planJson
);
}
...
...
src/MissionManager/PlanMasterController.h
View file @
c7a171eb
...
...
@@ -91,6 +91,12 @@ public:
Vehicle
*
controllerVehicle
(
void
)
{
return
_controllerVehicle
;
}
Vehicle
*
managerVehicle
(
void
)
{
return
_managerVehicle
;
}
static
const
int
kPlanFileVersion
;
static
const
char
*
kPlanFileType
;
static
const
char
*
kJsonMissionObjectKey
;
static
const
char
*
kJsonGeoFenceObjectKey
;
static
const
char
*
kJsonRallyPointsObjectKey
;
signals:
void
containsItemsChanged
(
bool
containsItems
);
void
syncInProgressChanged
(
void
);
...
...
@@ -124,9 +130,4 @@ private:
bool
_sendRallyPoints
;
QString
_currentPlanFile
;
static
const
int
_planFileVersion
;
static
const
char
*
_planFileType
;
static
const
char
*
_jsonMissionObjectKey
;
static
const
char
*
_jsonGeoFenceObjectKey
;
static
const
char
*
_jsonRallyPointsObjectKey
;
};
src/api/QGCCorePlugin.cc
View file @
c7a171eb
...
...
@@ -28,22 +28,22 @@ class QGCCorePlugin_p
{
public:
QGCCorePlugin_p
()
:
pGeneral
(
NULL
)
,
pCommLinks
(
NULL
)
,
pOfflineMaps
(
NULL
)
,
pMAVLink
(
NULL
)
,
pConsole
(
NULL
)
,
pHelp
(
NULL
)
:
pGeneral
(
nullptr
)
,
pCommLinks
(
nullptr
)
,
pOfflineMaps
(
nullptr
)
,
pMAVLink
(
nullptr
)
,
pConsole
(
nullptr
)
,
pHelp
(
nullptr
)
#if defined(QT_DEBUG)
,
pMockLink
(
NULL
)
,
pDebug
(
NULL
)
,
pMockLink
(
nullptr
)
,
pDebug
(
nullptr
)
#endif
,
defaultOptions
(
NULL
)
,
valuesPageWidgetInfo
(
NULL
)
,
cameraPageWidgetInfo
(
NULL
)
,
videoPageWidgetInfo
(
NULL
)
,
healthPageWidgetInfo
(
NULL
)
,
vibrationPageWidgetInfo
(
NULL
)
,
defaultOptions
(
nullptr
)
,
valuesPageWidgetInfo
(
nullptr
)
,
cameraPageWidgetInfo
(
nullptr
)
,
videoPageWidgetInfo
(
nullptr
)
,
healthPageWidgetInfo
(
nullptr
)
,
vibrationPageWidgetInfo
(
nullptr
)
{
}
...
...
@@ -119,35 +119,35 @@ QVariantList &QGCCorePlugin::settingsPages()
{
if
(
!
_p
->
pGeneral
)
{
_p
->
pGeneral
=
new
QmlComponentInfo
(
tr
(
"General"
),
QUrl
::
fromUserInput
(
"qrc:/qml/GeneralSettings.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/gear-white.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pGeneral
));
QUrl
::
fromUserInput
(
"qrc:/qml/GeneralSettings.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/gear-white.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pGeneral
)
));
_p
->
pCommLinks
=
new
QmlComponentInfo
(
tr
(
"Comm Links"
),
QUrl
::
fromUserInput
(
"qrc:/qml/LinkSettings.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/waves.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pCommLinks
));
QUrl
::
fromUserInput
(
"qrc:/qml/LinkSettings.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/waves.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pCommLinks
)
));
_p
->
pOfflineMaps
=
new
QmlComponentInfo
(
tr
(
"Offline Maps"
),
QUrl
::
fromUserInput
(
"qrc:/qml/OfflineMap.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/waves.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pOfflineMaps
));
QUrl
::
fromUserInput
(
"qrc:/qml/OfflineMap.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/waves.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pOfflineMaps
)
));
_p
->
pMAVLink
=
new
QmlComponentInfo
(
tr
(
"MAVLink"
),
QUrl
::
fromUserInput
(
"qrc:/qml/MavlinkSettings.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/waves.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pMAVLink
));
QUrl
::
fromUserInput
(
"qrc:/qml/MavlinkSettings.qml"
),
QUrl
::
fromUserInput
(
"qrc:/res/waves.svg"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pMAVLink
)
));
_p
->
pConsole
=
new
QmlComponentInfo
(
tr
(
"Console"
),
QUrl
::
fromUserInput
(
"qrc:/qml/QGroundControl/Controls/AppMessages.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pConsole
));
QUrl
::
fromUserInput
(
"qrc:/qml/QGroundControl/Controls/AppMessages.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pConsole
)
));
_p
->
pHelp
=
new
QmlComponentInfo
(
tr
(
"Help"
),
QUrl
::
fromUserInput
(
"qrc:/qml/HelpSettings.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pHelp
));
QUrl
::
fromUserInput
(
"qrc:/qml/HelpSettings.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pHelp
)
));
#if defined(QT_DEBUG)
//-- These are always present on Debug builds
_p
->
pMockLink
=
new
QmlComponentInfo
(
tr
(
"Mock Link"
),
QUrl
::
fromUserInput
(
"qrc:/qml/MockLink.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pMockLink
));
QUrl
::
fromUserInput
(
"qrc:/qml/MockLink.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pMockLink
)
));
_p
->
pDebug
=
new
QmlComponentInfo
(
tr
(
"Debug"
),
QUrl
::
fromUserInput
(
"qrc:/qml/DebugWindow.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
(
QmlComponentInfo
*
)
_p
->
pDebug
));
QUrl
::
fromUserInput
(
"qrc:/qml/DebugWindow.qml"
));
_p
->
settingsList
.
append
(
QVariant
::
fromValue
(
reinterpret_cast
<
QmlComponentInfo
*>
(
_p
->
pDebug
)
));
#endif
}
return
_p
->
settingsList
;
...
...
src/api/QGCCorePlugin.h
View file @
c7a171eb
...
...
@@ -32,6 +32,7 @@ class Vehicle;
class
LinkInterface
;
class
QmlObjectListModel
;
class
VideoReceiver
;
class
PlanMasterController
;
class
QGCCorePlugin
:
public
QGCTool
{
...
...
@@ -88,7 +89,7 @@ public:
virtual
QString
showAdvancedUIMessage
(
void
)
const
;
/// @return An instance of an alternate position source (or NULL if not available)
virtual
QGeoPositionInfoSource
*
createPositionSource
(
QObject
*
parent
)
{
Q_UNUSED
(
parent
);
return
NULL
;
}
virtual
QGeoPositionInfoSource
*
createPositionSource
(
QObject
*
parent
)
{
Q_UNUSED
(
parent
);
return
nullptr
;
}
/// Allows a plugin to override the specified color name from the palette
virtual
void
paletteOverride
(
QString
colorName
,
QGCPalette
::
PaletteColorInfo_t
&
colorInfo
);
...
...
@@ -110,6 +111,20 @@ public:
/// should derive from QmlComponentInfo and set the url property.
virtual
QmlObjectListModel
*
customMapItems
(
void
);
/// Allows custom builds to add custom items to the plan file. Either before the document is
/// created or after.
virtual
void
preSaveToJson
(
PlanMasterController
*
pController
,
QJsonObject
&
json
)
{
Q_UNUSED
(
pController
);
Q_UNUSED
(
json
);
}
virtual
void
postSaveToJson
(
PlanMasterController
*
pController
,
QJsonObject
&
json
)
{
Q_UNUSED
(
pController
);
Q_UNUSED
(
json
);
}
/// Same for the specific "mission" portion
virtual
void
preSaveToMissionJson
(
PlanMasterController
*
pController
,
QJsonObject
&
missionJson
)
{
Q_UNUSED
(
pController
);
Q_UNUSED
(
missionJson
);
}
virtual
void
postSaveToMissionJson
(
PlanMasterController
*
pController
,
QJsonObject
&
missionJson
)
{
Q_UNUSED
(
pController
);
Q_UNUSED
(
missionJson
);
}
/// Allows custom builds to load custom items from the plan file. Either before the document is
/// parsed or after.
virtual
void
preLoadFromJson
(
PlanMasterController
*
pController
,
QJsonObject
&
json
)
{
Q_UNUSED
(
pController
);
Q_UNUSED
(
json
);
}
virtual
void
postLoadFromJson
(
PlanMasterController
*
pController
,
QJsonObject
&
json
)
{
Q_UNUSED
(
pController
);
Q_UNUSED
(
json
);
}
bool
showTouchAreas
(
void
)
const
{
return
_showTouchAreas
;
}
bool
showAdvancedUI
(
void
)
const
{
return
_showAdvancedUI
;
}
void
setShowTouchAreas
(
bool
show
);
...
...
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