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
4544f671
Commit
4544f671
authored
Mar 27, 2017
by
Don Gagne
Committed by
GitHub
Mar 27, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4869 from DonLakeFlyer/PlanSync
More work on Plan sync user model
parents
62fb732c
12b1624e
Changes
12
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
514 additions
and
429 deletions
+514
-429
CenterMapDropPanel.qml
src/FlightMap/Widgets/CenterMapDropPanel.qml
+2
-2
MissionController.cc
src/MissionManager/MissionController.cc
+40
-12
MissionController.h
src/MissionManager/MissionController.h
+8
-0
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+8
-16
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+7
-5
MissionItemEditor.qml
src/PlanView/MissionItemEditor.qml
+2
-2
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+59
-10
PlanToolBar.qml
src/PlanView/PlanToolBar.qml
+0
-1
PlanView.qml
src/PlanView/PlanView.qml
+366
-381
App.SettingsGroup.json
src/Settings/App.SettingsGroup.json
+7
-0
AppSettings.cc
src/Settings/AppSettings.cc
+11
-0
AppSettings.h
src/Settings/AppSettings.h
+4
-0
No files found.
src/FlightMap/Widgets/CenterMapDropPanel.qml
View file @
4544f671
...
@@ -65,11 +65,11 @@ ColumnLayout {
...
@@ -65,11 +65,11 @@ ColumnLayout {
QGCButton
{
QGCButton
{
text
:
qsTr
(
"
Current Location
"
)
text
:
qsTr
(
"
Current Location
"
)
Layout.fillWidth
:
true
Layout.fillWidth
:
true
enabled
:
mainWindow
.
gcsPosition
.
isValid
enabled
:
_map
.
gcsPosition
.
isValid
onClicked
:
{
onClicked
:
{
dropPanel
.
hide
()
dropPanel
.
hide
()
map
.
center
=
mainWindow
.
gcsPosition
map
.
center
=
_map
.
gcsPosition
}
}
}
}
...
...
src/MissionManager/MissionController.cc
View file @
4544f671
...
@@ -56,6 +56,7 @@ MissionController::MissionController(QObject *parent)
...
@@ -56,6 +56,7 @@ MissionController::MissionController(QObject *parent)
,
_queuedSend
(
false
)
,
_queuedSend
(
false
)
,
_surveyMissionItemName
(
tr
(
"Survey"
))
,
_surveyMissionItemName
(
tr
(
"Survey"
))
,
_fwLandingMissionItemName
(
tr
(
"Fixed Wing Landing"
))
,
_fwLandingMissionItemName
(
tr
(
"Fixed Wing Landing"
))
,
_appSettings
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
())
{
{
_missionFlightStatus
.
maxTelemetryDistance
=
0
;
_missionFlightStatus
.
maxTelemetryDistance
=
0
;
_missionFlightStatus
.
totalDistance
=
0
;
_missionFlightStatus
.
totalDistance
=
0
;
...
@@ -449,18 +450,18 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
...
@@ -449,18 +450,18 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
// Mission Settings
// Mission Settings
QGeoCoordinate
homeCoordinate
;
QGeoCoordinate
homeCoordinate
;
SettingsManager
*
settingsManager
=
qgcApp
()
->
toolbox
()
->
settingsManager
();
AppSettings
*
appSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
();
if
(
!
JsonHelper
::
loadGeoCoordinate
(
json
[
_jsonPlannedHomePositionKey
],
true
/* altitudeRequired */
,
homeCoordinate
,
errorString
))
{
if
(
!
JsonHelper
::
loadGeoCoordinate
(
json
[
_jsonPlannedHomePositionKey
],
true
/* altitudeRequired */
,
homeCoordinate
,
errorString
))
{
return
false
;
return
false
;
}
}
if
(
json
.
contains
(
_jsonVehicleTypeKey
)
&&
vehicle
->
isOfflineEditingVehicle
())
{
if
(
json
.
contains
(
_jsonVehicleTypeKey
)
&&
vehicle
->
isOfflineEditingVehicle
())
{
settingsManager
->
appSettings
()
->
offlineEditingVehicleType
()
->
setRawValue
(
json
[
_jsonVehicleTypeKey
].
toDouble
());
appSettings
->
offlineEditingVehicleType
()
->
setRawValue
(
json
[
_jsonVehicleTypeKey
].
toDouble
());
}
}
if
(
json
.
contains
(
_jsonCruiseSpeedKey
))
{
if
(
json
.
contains
(
_jsonCruiseSpeedKey
))
{
settingsManager
->
appSettings
()
->
offlineEditingCruiseSpeed
()
->
setRawValue
(
json
[
_jsonCruiseSpeedKey
].
toDouble
());
appSettings
->
offlineEditingCruiseSpeed
()
->
setRawValue
(
json
[
_jsonCruiseSpeedKey
].
toDouble
());
}
}
if
(
json
.
contains
(
_jsonHoverSpeedKey
))
{
if
(
json
.
contains
(
_jsonHoverSpeedKey
))
{
settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
setRawValue
(
json
[
_jsonHoverSpeedKey
].
toDouble
());
appSettings
->
offlineEditingHoverSpeed
()
->
setRawValue
(
json
[
_jsonHoverSpeedKey
].
toDouble
());
}
}
MissionSettingsItem
*
settingsItem
=
new
MissionSettingsItem
(
vehicle
,
visualItems
);
MissionSettingsItem
*
settingsItem
=
new
MissionSettingsItem
(
vehicle
,
visualItems
);
...
@@ -647,17 +648,27 @@ void MissionController::loadFromFile(const QString& filename)
...
@@ -647,17 +648,27 @@ void MissionController::loadFromFile(const QString& filename)
_initAllVisualItems
();
_initAllVisualItems
();
// Split the filename into directory and filename
QString
filenameOnly
=
filename
;
QString
filenameOnly
=
filename
;
int
lastSepIndex
=
filename
.
lastIndexOf
(
QStringLiteral
(
"/"
));
int
lastSepIndex
=
filename
.
lastIndexOf
(
QStringLiteral
(
"/"
));
if
(
lastSepIndex
!=
-
1
)
{
if
(
lastSepIndex
!=
-
1
)
{
filenameOnly
=
filename
.
right
(
filename
.
length
()
-
lastSepIndex
-
1
);
filenameOnly
=
filename
.
right
(
filename
.
length
()
-
lastSepIndex
-
1
);
}
}
QString
directoryOnly
=
filename
.
left
(
filename
.
length
()
-
filenameOnly
.
length
()
-
1
);
QString
extension
=
AppSettings
::
missionFileExtension
;
QString
extension
=
AppSettings
::
missionFileExtension
;
if
(
filenameOnly
.
endsWith
(
"."
+
extension
))
{
if
(
filenameOnly
.
endsWith
(
"."
+
extension
))
{
filenameOnly
=
filenameOnly
.
left
(
filenameOnly
.
length
()
-
extension
.
length
()
-
1
);
filenameOnly
=
filenameOnly
.
left
(
filenameOnly
.
length
()
-
extension
.
length
()
-
1
);
}
}
_settingsItem
->
missionName
()
->
setRawValue
(
filenameOnly
);
_settingsItem
->
missionName
()
->
setRawValue
(
filenameOnly
);
if
(
directoryOnly
==
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
missionSavePath
())
{
QString
emptyString
;
_settingsItem
->
setLoadedMissionDirectory
(
emptyString
);
}
else
{
_settingsItem
->
setLoadedMissionDirectory
(
directoryOnly
);
}
_settingsItem
->
setExistingMission
(
true
);
_settingsItem
->
setExistingMission
(
true
);
sendToVehicle
();
sendToVehicle
();
...
@@ -704,8 +715,6 @@ bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filen
...
@@ -704,8 +715,6 @@ bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filen
void
MissionController
::
saveToFile
(
const
QString
&
filename
)
void
MissionController
::
saveToFile
(
const
QString
&
filename
)
{
{
qDebug
()
<<
filename
;
if
(
filename
.
isEmpty
())
{
if
(
filename
.
isEmpty
())
{
return
;
return
;
}
}
...
@@ -718,7 +727,7 @@ void MissionController::saveToFile(const QString& filename)
...
@@ -718,7 +727,7 @@ void MissionController::saveToFile(const QString& filename)
QFile
file
(
missionFilename
);
QFile
file
(
missionFilename
);
if
(
!
file
.
open
(
QIODevice
::
WriteOnly
|
QIODevice
::
Text
))
{
if
(
!
file
.
open
(
QIODevice
::
WriteOnly
|
QIODevice
::
Text
))
{
qgcApp
()
->
showMessage
(
file
.
errorString
(
));
qgcApp
()
->
showMessage
(
tr
(
"Mission save %1 : %2"
).
arg
(
filename
).
arg
(
file
.
errorString
()
));
}
else
{
}
else
{
QJsonObject
missionFileObject
;
// top level json object
QJsonObject
missionFileObject
;
// top level json object
...
@@ -1596,9 +1605,17 @@ bool MissionController::missionInProgress(void) const
...
@@ -1596,9 +1605,17 @@ bool MissionController::missionInProgress(void) const
void
MissionController
::
save
(
void
)
void
MissionController
::
save
(
void
)
{
{
// Save to file if the mission is named
// Save to file if the mission is named
QString
missionFullPath
=
_settingsItem
->
missionFullPath
()
->
rawValue
().
toString
();
if
(
!
missionFullPath
.
isEmpty
())
{
QString
missionDir
=
_settingsItem
->
loadedMissionDirectory
();
saveToFile
(
missionFullPath
);
if
(
missionDir
.
isEmpty
())
{
missionDir
=
_appSettings
->
missionSavePath
();
}
bool
savedToFile
=
false
;
QString
missionName
=
_settingsItem
->
missionName
()
->
rawValue
().
toString
();
if
(
!
missionDir
.
isEmpty
()
&&
!
missionName
.
isEmpty
())
{
savedToFile
=
true
;
saveToFile
(
missionDir
+
"/"
+
missionName
);
}
}
// Send to vehicle if we are connected
// Send to vehicle if we are connected
...
@@ -1606,11 +1623,22 @@ void MissionController::save(void)
...
@@ -1606,11 +1623,22 @@ void MissionController::save(void)
sendToVehicle
();
sendToVehicle
();
}
}
_settingsItem
->
setExistingMission
(
_visualItems
->
count
()
>
1
&&
!
missionFullPath
.
isEmpty
()
);
_settingsItem
->
setExistingMission
(
savedToFile
);
}
}
void
MissionController
::
clearMission
(
void
)
void
MissionController
::
clearMission
(
void
)
{
// We need to save the mission information around removeAll all since it delete/recreates settings item
QString
missionName
=
_settingsItem
->
missionName
()
->
rawValue
().
toString
();
QString
loadedMissionDirectory
=
_settingsItem
->
loadedMissionDirectory
();
bool
existingMission
=
_settingsItem
->
existingMission
();
removeAll
();
_settingsItem
->
missionName
()
->
setRawValue
(
missionName
);
_settingsItem
->
setLoadedMissionDirectory
(
loadedMissionDirectory
);
_settingsItem
->
setExistingMission
(
existingMission
);
}
void
MissionController
::
closeMission
(
void
)
{
{
removeAll
();
removeAll
();
save
();
}
}
src/MissionManager/MissionController.h
View file @
4544f671
...
@@ -23,6 +23,7 @@ class CoordinateVector;
...
@@ -23,6 +23,7 @@ class CoordinateVector;
class
VisualMissionItem
;
class
VisualMissionItem
;
class
MissionItem
;
class
MissionItem
;
class
MissionSettingsItem
;
class
MissionSettingsItem
;
class
AppSettings
;
Q_DECLARE_LOGGING_CATEGORY
(
MissionControllerLog
)
Q_DECLARE_LOGGING_CATEGORY
(
MissionControllerLog
)
...
@@ -88,9 +89,15 @@ public:
...
@@ -88,9 +89,15 @@ public:
/// Sends the mission items to the specified vehicle
/// Sends the mission items to the specified vehicle
static
void
sendItemsToVehicle
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualMissionItems
);
static
void
sendItemsToVehicle
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualMissionItems
);
/// Saves the mission to file if any and sends to vehicle
Q_INVOKABLE
void
save
(
void
);
Q_INVOKABLE
void
save
(
void
);
/// Removes all items from the mission saving and sending as needed
Q_INVOKABLE
void
clearMission
(
void
);
Q_INVOKABLE
void
clearMission
(
void
);
/// Closes the mission, saving and sending as needed before closing
Q_INVOKABLE
void
closeMission
(
void
);
// Overrides from PlanElementController
// Overrides from PlanElementController
void
start
(
bool
editMode
)
final
;
void
start
(
bool
editMode
)
final
;
void
startStaticActiveVehicle
(
Vehicle
*
vehicle
)
final
;
void
startStaticActiveVehicle
(
Vehicle
*
vehicle
)
final
;
...
@@ -193,6 +200,7 @@ private:
...
@@ -193,6 +200,7 @@ private:
MissionFlightStatus_t
_missionFlightStatus
;
MissionFlightStatus_t
_missionFlightStatus
;
QString
_surveyMissionItemName
;
QString
_surveyMissionItemName
;
QString
_fwLandingMissionItemName
;
QString
_fwLandingMissionItemName
;
AppSettings
*
_appSettings
;
static
const
char
*
_settingsGroup
;
static
const
char
*
_settingsGroup
;
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
4544f671
...
@@ -24,7 +24,6 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL
...
@@ -24,7 +24,6 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL
const
char
*
MissionSettingsItem
::
jsonComplexItemTypeValue
=
"MissionSettings"
;
const
char
*
MissionSettingsItem
::
jsonComplexItemTypeValue
=
"MissionSettings"
;
const
char
*
MissionSettingsItem
::
_missionNameName
=
"MissionName"
;
const
char
*
MissionSettingsItem
::
_missionNameName
=
"MissionName"
;
const
char
*
MissionSettingsItem
::
_missionFullPathName
=
"MissionFullPath"
;
const
char
*
MissionSettingsItem
::
_plannedHomePositionAltitudeName
=
"PlannedHomePositionAltitude"
;
const
char
*
MissionSettingsItem
::
_plannedHomePositionAltitudeName
=
"PlannedHomePositionAltitude"
;
const
char
*
MissionSettingsItem
::
_missionFlightSpeedName
=
"FlightSpeed"
;
const
char
*
MissionSettingsItem
::
_missionFlightSpeedName
=
"FlightSpeed"
;
const
char
*
MissionSettingsItem
::
_missionEndActionName
=
"MissionEndAction"
;
const
char
*
MissionSettingsItem
::
_missionEndActionName
=
"MissionEndAction"
;
...
@@ -36,7 +35,6 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
...
@@ -36,7 +35,6 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
,
_existingMission
(
false
)
,
_existingMission
(
false
)
,
_specifyMissionFlightSpeed
(
false
)
,
_specifyMissionFlightSpeed
(
false
)
,
_missionNameFact
(
0
,
_missionNameName
,
FactMetaData
::
valueTypeString
)
,
_missionNameFact
(
0
,
_missionNameName
,
FactMetaData
::
valueTypeString
)
,
_missionFullPathFact
(
0
,
_missionFullPathName
,
FactMetaData
::
valueTypeString
)
,
_plannedHomePositionAltitudeFact
(
0
,
_plannedHomePositionAltitudeName
,
FactMetaData
::
valueTypeDouble
)
,
_plannedHomePositionAltitudeFact
(
0
,
_plannedHomePositionAltitudeName
,
FactMetaData
::
valueTypeDouble
)
,
_missionFlightSpeedFact
(
0
,
_missionFlightSpeedName
,
FactMetaData
::
valueTypeDouble
)
,
_missionFlightSpeedFact
(
0
,
_missionFlightSpeedName
,
FactMetaData
::
valueTypeDouble
)
,
_missionEndActionFact
(
0
,
_missionEndActionName
,
FactMetaData
::
valueTypeUint32
)
,
_missionEndActionFact
(
0
,
_missionEndActionName
,
FactMetaData
::
valueTypeUint32
)
...
@@ -65,8 +63,6 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
...
@@ -65,8 +63,6 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
setHomePositionSpecialCase
(
true
);
setHomePositionSpecialCase
(
true
);
connect
(
&
_missionNameFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_missionNameChanged
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
...
@@ -416,18 +412,6 @@ void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
...
@@ -416,18 +412,6 @@ void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
}
}
}
}
void
MissionSettingsItem
::
_missionNameChanged
(
QVariant
value
)
{
QString
missionDir
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
missionSavePath
();
QString
missionName
=
value
.
toString
();
if
(
missionName
.
isEmpty
())
{
_missionFullPathFact
.
setRawValue
(
QString
());
}
else
{
_missionFullPathFact
.
setRawValue
(
missionDir
+
"/"
+
missionName
);
}
}
void
MissionSettingsItem
::
setExistingMission
(
bool
existingMission
)
void
MissionSettingsItem
::
setExistingMission
(
bool
existingMission
)
{
{
if
(
existingMission
!=
_existingMission
)
{
if
(
existingMission
!=
_existingMission
)
{
...
@@ -435,3 +419,11 @@ void MissionSettingsItem::setExistingMission(bool existingMission)
...
@@ -435,3 +419,11 @@ void MissionSettingsItem::setExistingMission(bool existingMission)
emit
existingMissionChanged
(
existingMission
);
emit
existingMissionChanged
(
existingMission
);
}
}
}
}
void
MissionSettingsItem
::
setLoadedMissionDirectory
(
QString
&
loadedMissionDirectory
)
{
if
(
_loadedMissionDirectory
!=
loadedMissionDirectory
)
{
_loadedMissionDirectory
=
loadedMissionDirectory
;
emit
loadedMissionDirectoryChanged
(
loadedMissionDirectory
);
}
}
src/MissionManager/MissionSettingsItem.h
View file @
4544f671
...
@@ -33,7 +33,7 @@ public:
...
@@ -33,7 +33,7 @@ public:
Q_ENUMS
(
MissionEndAction
)
Q_ENUMS
(
MissionEndAction
)
Q_PROPERTY
(
Fact
*
missionName
READ
missionName
CONSTANT
)
Q_PROPERTY
(
Fact
*
missionName
READ
missionName
CONSTANT
)
Q_PROPERTY
(
Fact
*
missionFullPath
READ
missionFullPath
CONSTANT
)
Q_PROPERTY
(
QString
loadedMissionDirectory
READ
loadedMissionDirectory
WRITE
setLoadedMissionDirectory
NOTIFY
loadedMissionDirectoryChanged
)
Q_PROPERTY
(
bool
existingMission
READ
existingMission
WRITE
setExistingMission
NOTIFY
existingMissionChanged
)
Q_PROPERTY
(
bool
existingMission
READ
existingMission
WRITE
setExistingMission
NOTIFY
existingMissionChanged
)
Q_PROPERTY
(
bool
specifyMissionFlightSpeed
READ
specifyMissionFlightSpeed
WRITE
setSpecifyMissionFlightSpeed
NOTIFY
specifyMissionFlightSpeedChanged
)
Q_PROPERTY
(
bool
specifyMissionFlightSpeed
READ
specifyMissionFlightSpeed
WRITE
setSpecifyMissionFlightSpeed
NOTIFY
specifyMissionFlightSpeedChanged
)
Q_PROPERTY
(
Fact
*
missionFlightSpeed
READ
missionFlightSpeed
CONSTANT
)
Q_PROPERTY
(
Fact
*
missionFlightSpeed
READ
missionFlightSpeed
CONSTANT
)
...
@@ -42,7 +42,6 @@ public:
...
@@ -42,7 +42,6 @@ public:
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Fact
*
missionName
(
void
)
{
return
&
_missionNameFact
;
}
Fact
*
missionName
(
void
)
{
return
&
_missionNameFact
;
}
Fact
*
missionFullPath
(
void
)
{
return
&
_missionFullPathFact
;
}
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
missionFlightSpeed
(
void
)
{
return
&
_missionFlightSpeedFact
;
}
Fact
*
missionFlightSpeed
(
void
)
{
return
&
_missionFlightSpeedFact
;
}
Fact
*
missionEndAction
(
void
)
{
return
&
_missionEndActionFact
;
}
Fact
*
missionEndAction
(
void
)
{
return
&
_missionEndActionFact
;
}
...
@@ -63,6 +62,10 @@ public:
...
@@ -63,6 +62,10 @@ public:
/// @return true: Mission end action was added
/// @return true: Mission end action was added
bool
addMissionEndAction
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QObject
*
missionItemParent
);
bool
addMissionEndAction
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QObject
*
missionItemParent
);
// Returns the directory the misiosn was loaded from. Empty string is laoded from normal savePath.
QString
loadedMissionDirectory
(
void
)
const
{
return
_loadedMissionDirectory
;
}
void
setLoadedMissionDirectory
(
QString
&
loadedMissionDirectory
);
// Overrides from ComplexMissionItem
// Overrides from ComplexMissionItem
double
complexDistance
(
void
)
const
final
;
double
complexDistance
(
void
)
const
final
;
...
@@ -102,23 +105,23 @@ public:
...
@@ -102,23 +105,23 @@ public:
signals:
signals:
void
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
existingMissionChanged
(
bool
existingMission
);
void
existingMissionChanged
(
bool
existingMission
);
void
loadedMissionDirectoryChanged
(
QString
&
loadedMissionDirectory
);
private
slots
:
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirty
(
void
);
void
_setDirty
(
void
);
void
_cameraSectionDirtyChanged
(
bool
dirty
);
void
_cameraSectionDirtyChanged
(
bool
dirty
);
void
_updateAltitudeInCoordinate
(
QVariant
value
);
void
_updateAltitudeInCoordinate
(
QVariant
value
);
void
_missionNameChanged
(
QVariant
value
);
private:
private:
bool
_existingMission
;
bool
_existingMission
;
bool
_specifyMissionFlightSpeed
;
bool
_specifyMissionFlightSpeed
;
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
Fact
_missionNameFact
;
Fact
_missionNameFact
;
Fact
_missionFullPathFact
;
Fact
_plannedHomePositionAltitudeFact
;
Fact
_plannedHomePositionAltitudeFact
;
Fact
_missionFlightSpeedFact
;
Fact
_missionFlightSpeedFact
;
Fact
_missionEndActionFact
;
Fact
_missionEndActionFact
;
QString
_loadedMissionDirectory
;
CameraSection
_cameraSection
;
CameraSection
_cameraSection
;
int
_sequenceNumber
;
int
_sequenceNumber
;
...
@@ -127,7 +130,6 @@ private:
...
@@ -127,7 +130,6 @@ private:
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_missionNameName
;
static
const
char
*
_missionNameName
;
static
const
char
*
_missionFullPathName
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_missionFlightSpeedName
;
static
const
char
*
_missionFlightSpeedName
;
static
const
char
*
_missionEndActionName
;
static
const
char
*
_missionEndActionName
;
...
...
src/PlanView/MissionItemEditor.qml
View file @
4544f671
...
@@ -12,8 +12,7 @@ import QGroundControl.Palette 1.0
...
@@ -12,8 +12,7 @@ import QGroundControl.Palette 1.0
/// Mission item edit control
/// Mission item edit control
Rectangle
{
Rectangle
{
id
:
_root
id
:
_root
height
:
editorLoader
.
y
+
editorLoader
.
height
+
(
_margin
*
2
)
height
:
editorLoader
.
y
+
editorLoader
.
height
+
(
_margin
*
2
)
color
:
_currentItem
?
qgcPal
.
primaryButton
:
qgcPal
.
windowShade
color
:
_currentItem
?
qgcPal
.
primaryButton
:
qgcPal
.
windowShade
radius
:
_radius
radius
:
_radius
...
@@ -21,6 +20,7 @@ Rectangle {
...
@@ -21,6 +20,7 @@ Rectangle {
property
var
map
///< Map control
property
var
map
///< Map control
property
var
missionItem
///< MissionItem associated with this editor
property
var
missionItem
///< MissionItem associated with this editor
property
bool
readOnly
///< true: read only view, false: full editing view
property
bool
readOnly
///< true: read only view, false: full editing view
property
var
rootQgcView
signal
clicked
signal
clicked
signal
remove
signal
remove
...
...
src/PlanView/MissionSettingsEditor.qml
View file @
4544f671
...
@@ -35,6 +35,7 @@ Rectangle {
...
@@ -35,6 +35,7 @@ Rectangle {
property
bool
_noMissionName
:
missionItem
.
missionName
.
valueString
===
""
property
bool
_noMissionName
:
missionItem
.
missionName
.
valueString
===
""
property
bool
_showMissionList
:
_noMissionItemsAdded
&&
(
_noMissionName
||
_newMissionAlreadyExists
)
property
bool
_showMissionList
:
_noMissionItemsAdded
&&
(
_noMissionName
||
_newMissionAlreadyExists
)
property
bool
_existingMissionLoaded
:
missionItem
.
existingMission
property
bool
_existingMissionLoaded
:
missionItem
.
existingMission
property
var
_appSettings
:
QGroundControl
.
settingsManager
.
appSettings
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle
"
)
...
@@ -97,10 +98,36 @@ Rectangle {
...
@@ -97,10 +98,36 @@ Rectangle {
visible
:
!
_existingMissionLoaded
&&
_newMissionAlreadyExists
visible
:
!
_existingMissionLoaded
&&
_newMissionAlreadyExists
}
}
QGCButton
{
FactCheckBox
{
text
:
qsTr
(
"
Clear mission
"
)
id
:
automaticUploadCheckbox
visible
:
!
_noMissionItemsAdded
text
:
qsTr
(
"
Automatically upload on exit
"
)
onClicked
:
missionController
.
clearMission
()
fact
:
_appSettings
.
automaticMissionUpload
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
QGCButton
{
text
:
qsTr
(
"
Clear
"
)
visible
:
!
_noMissionItemsAdded
Layout.fillWidth
:
true
onClicked
:
missionController
.
clearMission
()
}
QGCButton
{
text
:
qsTr
(
"
Close
"
)
visible
:
!
_noMissionItemsAdded
Layout.fillWidth
:
true
onClicked
:
missionController
.
closeMission
()
}
QGCButton
{
text
:
qsTr
(
"
Upload
"
)
visible
:
!
_noMissionItemsAdded
&&
!
automaticUploadCheckbox
.
checked
Layout.fillWidth
:
true
onClicked
:
missionController
.
sendToVehicle
()
}
}
}
Loader
{
Loader
{
...
@@ -132,14 +159,36 @@ Rectangle {
...
@@ -132,14 +159,36 @@ Rectangle {
showSpacer
:
false
showSpacer
:
false
}
}
QGCButton
{
RowLayout
{
anchors.left
:
parent
.
left
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
text
:
qsTr
(
"
Load from Vehicle
"
)
visible
:
!
_offlineEditing
onClicked
:
{
QGCButton
{
missionController
.
loadFromVehicle
()
text
:
qsTr
(
"
From Vehicle
"
)
visible
:
!
_offlineEditing
Layout.fillWidth
:
true
onClicked
:
missionController
.
loadFromVehicle
()
}
QGCButton
{
text
:
qsTr
(
"
Browse
"
)
Layout.fillWidth
:
true
onClicked
:
fileDialog
.
openForLoad
()
QGCFileDialog
{
id
:
fileDialog
qgcView
:
rootQgcView
title
:
qsTr
(
"
Select mission file
"
)
selectExisting
:
true
folder
:
_appSettings
.
missionSavePath
fileExtension
:
_appSettings
.
missionFileExtension
nameFilters
:
[
qsTr
(
"
Mission Files (*.%1)
"
).
arg
(
fileExtension
)
,
qsTr
(
"
All Files (*.*)
"
)
]
onAcceptedForLoad
:
{
missionController
.
loadFromFile
(
file
)
fileDialog
.
close
()
}
}
}
}
}
}
...
@@ -337,5 +386,5 @@ Rectangle {
...
@@ -337,5 +386,5 @@ Rectangle {
}
}
}
}
}
// Column
}
// Column
}
}
// Deferred loader
}
// Rectangle
}
// Rectangle
src/PlanView/PlanToolBar.qml
View file @
4544f671
...
@@ -80,7 +80,6 @@ Rectangle {
...
@@ -80,7 +80,6 @@ Rectangle {
checked
:
false
checked
:
false
onClicked
:
{
onClicked
:
{
console
.
log
(
"
Leave plan clicked
"
)
checked
=
false
checked
=
false
missionController
.
saveOnSwitch
()
missionController
.
saveOnSwitch
()
showFlyView
()
showFlyView
()
...
...
src/PlanView/PlanView.qml
View file @
4544f671
...
@@ -48,6 +48,7 @@ QGCView {
...
@@ -48,6 +48,7 @@ QGCView {
property
bool
_lightWidgetBorders
:
editorMap
.
isSatelliteMap
property
bool
_lightWidgetBorders
:
editorMap
.
isSatelliteMap
property
bool
_addWaypointOnClick
:
false
property
bool
_addWaypointOnClick
:
false
property
bool
_singleComplexItem
:
missionController
.
complexMissionItemNames
.
length
===
1
property
bool
_singleComplexItem
:
missionController
.
complexMissionItemNames
.
length
===
1
property
real
_toolbarHeight
:
_qgcView
.
height
-
ScreenTools
.
availableHeight
/// The controller which should be called for load/save, send to/from vehicle calls
/// The controller which should be called for load/save, send to/from vehicle calls
property
var
_syncDropDownController
:
missionController
property
var
_syncDropDownController
:
missionController
...
@@ -321,437 +322,421 @@ QGCView {
...
@@ -321,437 +322,421 @@ QGCView {
anchors.left
:
parent
.
left
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
Item
{
FlightMap
{
anchors.fill
:
parent
id
:
editorMap
height
:
_qgcView
.
height
anchors.bottom
:
parent
.
bottom
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
//rightPanel.left
mapName
:
"
MissionEditor
"
FlightMap
{
// This is the center rectangle of the map which is not obscured by tools
id
:
editorMap
property
rect
centerViewport
:
Qt
.
rect
(
_leftToolWidth
,
_toolbarHeight
,
editorMap
.
width
-
_leftToolWidth
-
_rightPanelWidth
,
editorMap
.
height
-
_statusHeight
-
_toolbarHeight
)
height
:
_qgcView
.
height
anchors.bottom
:
parent
.
bottom
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
mapName
:
"
MissionEditor
"
// This is the center rectangle of the map which is not obscured by tools
property
real
_leftToolWidth
:
toolStrip
.
x
+
toolStrip
.
width
property
rect
centerViewport
:
Qt
.
rect
(
_leftToolWidth
,
_toolbarHeight
,
editorMap
.
width
-
_leftToolWidth
-
_rightPanelWidth
,
editorMap
.
height
-
_statusHeight
-
_toolbarHeight
)
property
real
_statusHeight
:
waypointValuesDisplay
.
visible
?
editorMap
.
height
-
waypointValuesDisplay
.
y
:
0
property
real
_toolbarHeight
:
_qgcView
.
height
-
ScreenTools
.
availableHeight
readonly
property
real
animationDuration
:
500
property
real
_leftToolWidth
:
toolStrip
.
x
+
toolStrip
.
width
property
real
_statusHeight
:
waypointValuesDisplay
.
visible
?
editorMap
.
height
-
waypointValuesDisplay
.
y
:
0
readonly
property
real
animationDuration
:
500
// Initial map position duplicates Fly view position
Component.onCompleted
:
editorMap
.
center
=
QGroundControl
.
flightMapPosition
// Initial map position duplicates Fly view position
Behavior
on
zoomLevel
{
Component.onCompleted
:
editorMap
.
center
=
QGroundControl
.
flightMapPosition
NumberAnimation
{
duration
:
editorMap
.
animationDuration
easing.type
:
Easing
.
InOutQuad
}
}
Behavior
on
zoomLevel
{
QGCMapPalette
{
id
:
mapPal
;
lightColors
:
editorMap
.
isSatelliteMap
}
NumberAnimation
{
duration
:
editorMap
.
animationDuration
MouseArea
{
easing.type
:
Easing
.
InOutQuad
//-- It's a whole lot faster to just fill parent and deal with top offset below
// than computing the coordinate offset.
anchors.fill
:
parent
onClicked
:
{
//-- Don't pay attention to items beneath the toolbar.
var
topLimit
=
parent
.
height
-
ScreenTools
.
availableHeight
if
(
mouse
.
y
<
topLimit
)
{
return
}
}
}
QGCMapPalette
{
id
:
mapPal
;
lightColors
:
editorMap
.
isSatelliteMap
}
var
coordinate
=
editorMap
.
toCoordinate
(
Qt
.
point
(
mouse
.
x
,
mouse
.
y
),
false
/* clipToViewPort */
)
coordinate
.
latitude
=
coordinate
.
latitude
.
toFixed
(
_decimalPlaces
)
coordinate
.
longitude
=
coordinate
.
longitude
.
toFixed
(
_decimalPlaces
)
coordinate
.
altitude
=
coordinate
.
altitude
.
toFixed
(
_decimalPlaces
)
MouseArea
{
switch
(
_editingLayer
)
{
//-- It's a whole lot faster to just fill parent and deal with top offset below
case
_layerMission
:
// than computing the coordinate offset.
if
(
_addWaypointOnClick
)
{
anchors.fill
:
parent
insertSimpleMissionItem
(
coordinate
,
missionController
.
visualItems
.
count
)
onClicked
:
{
//-- Don't pay attention to items beneath the toolbar.
var
topLimit
=
parent
.
height
-
ScreenTools
.
availableHeight
if
(
mouse
.
y
<
topLimit
)
{
return
}
}
break
var
coordinate
=
editorMap
.
toCoordinate
(
Qt
.
point
(
mouse
.
x
,
mouse
.
y
),
false
/* clipToViewPort */
)
case
_layerRallyPoints
:
coordinate
.
latitude
=
coordinate
.
latitude
.
toFixed
(
_decimalPlaces
)
if
(
rallyPointController
.
rallyPointsSupported
)
{
coordinate
.
longitude
=
coordinate
.
longitude
.
toFixed
(
_decimalPlaces
)
rallyPointController
.
addPoint
(
coordinate
)
coordinate
.
altitude
=
coordinate
.
altitude
.
toFixed
(
_decimalPlaces
)
switch
(
_editingLayer
)
{
case
_layerMission
:
if
(
_addWaypointOnClick
)
{
insertSimpleMissionItem
(
coordinate
,
missionController
.
visualItems
.
count
)
}
break
case
_layerRallyPoints
:
if
(
rallyPointController
.
rallyPointsSupported
)
{
rallyPointController
.
addPoint
(
coordinate
)
}
break
}
}
break
}
}
}
}
}
// We use this item to support dragging since dragging a MapQuickItem just doesn't seem to work
// We use this item to support dragging since dragging a MapQuickItem just doesn't seem to work
Rectangle
{
Rectangle
{
id
:
itemDragger
id
:
itemDragger
x
:
mapCoordinateIndicator
?
(
mapCoordinateIndicator
.
x
+
mapCoordinateIndicator
.
anchorPoint
.
x
-
(
itemDragger
.
width
/
2
))
:
100
x
:
mapCoordinateIndicator
?
(
mapCoordinateIndicator
.
x
+
mapCoordinateIndicator
.
anchorPoint
.
x
-
(
itemDragger
.
width
/
2
))
:
100
y
:
mapCoordinateIndicator
?
(
mapCoordinateIndicator
.
y
+
mapCoordinateIndicator
.
anchorPoint
.
y
-
(
itemDragger
.
height
/
2
))
:
100
y
:
mapCoordinateIndicator
?
(
mapCoordinateIndicator
.
y
+
mapCoordinateIndicator
.
anchorPoint
.
y
-
(
itemDragger
.
height
/
2
))
:
100
width
:
ScreenTools
.
defaultFontPixelHeight
*
3
width
:
ScreenTools
.
defaultFontPixelHeight
*
3
height
:
ScreenTools
.
defaultFontPixelHeight
*
3
height
:
ScreenTools
.
defaultFontPixelHeight
*
3
color
:
"
transparent
"
color
:
"
transparent
"
visible
:
false
visible
:
false
z
:
QGroundControl
.
zOrderMapItems
+
1
// Above item icons
z
:
QGroundControl
.
zOrderMapItems
+
1
// Above item icons
property
var
coordinateItem
property
var
coordinateItem
property
var
mapCoordinateIndicator
property
var
mapCoordinateIndicator
property
bool
preventCoordinateBindingLoop
:
false
property
bool
preventCoordinateBindingLoop
:
false
onXChanged
:
liveDrag
()
onXChanged
:
liveDrag
()
onYChanged
:
liveDrag
()
onYChanged
:
liveDrag
()
function
liveDrag
()
{
function
liveDrag
()
{
if
(
!
itemDragger
.
preventCoordinateBindingLoop
&&
Drag
.
active
)
{
if
(
!
itemDragger
.
preventCoordinateBindingLoop
&&
Drag
.
active
)
{
var
point
=
Qt
.
point
(
itemDragger
.
x
+
(
itemDragger
.
width
/
2
),
itemDragger
.
y
+
(
itemDragger
.
height
/
2
))
var
point
=
Qt
.
point
(
itemDragger
.
x
+
(
itemDragger
.
width
/
2
),
itemDragger
.
y
+
(
itemDragger
.
height
/
2
))
var
coordinate
=
editorMap
.
toCoordinate
(
point
,
false
/* clipToViewPort */
)
var
coordinate
=
editorMap
.
toCoordinate
(
point
,
false
/* clipToViewPort */
)
coordinate
.
altitude
=
itemDragger
.
coordinateItem
.
coordinate
.
altitude
coordinate
.
altitude
=
itemDragger
.
coordinateItem
.
coordinate
.
altitude
itemDragger
.
preventCoordinateBindingLoop
=
true
itemDragger
.
preventCoordinateBindingLoop
=
true
itemDragger
.
coordinateItem
.
coordinate
=
coordinate
itemDragger
.
coordinateItem
.
coordinate
=
coordinate
itemDragger
.
preventCoordinateBindingLoop
=
false
itemDragger
.
preventCoordinateBindingLoop
=
false
}
}
function
clearItem
()
{
itemDragger
.
visible
=
false
itemDragger
.
coordinateItem
=
undefined
itemDragger
.
mapCoordinateIndicator
=
undefined
}
Drag.active
:
itemDrag
.
drag
.
active
Drag.hotSpot.x
:
width
/
2
Drag.hotSpot.y
:
height
/
2
MouseArea
{
id
:
itemDrag
anchors.fill
:
parent
drag.target
:
parent
drag.minimumX
:
0
drag.minimumY
:
0
drag.maximumX
:
itemDragger
.
parent
.
width
-
parent
.
width
drag.maximumY
:
itemDragger
.
parent
.
height
-
parent
.
height
}
}
}
}
// Add the mission item visuals to the map
function
clearItem
()
{
Repeater
{
itemDragger
.
visible
=
false
model
:
missionController
.
visualItems
itemDragger
.
coordinateItem
=
undefined
itemDragger
.
mapCoordinateIndicator
=
undefined
delegate
:
MissionItemMapVisual
{
map
:
editorMap
onClicked
:
setCurrentItem
(
sequenceNumber
)
}
}
}
// Add lines between waypoints
Drag.active
:
itemDrag
.
drag
.
active
MissionLineView
{
Drag.hotSpot.x
:
width
/
2
model
:
_editingLayer
==
_layerMission
?
missionController
.
waypointLines
:
undefined
Drag.hotSpot.y
:
height
/
2
}
// Add the vehicles to the map
MouseArea
{
MapItemView
{
id
:
itemDrag
model
:
QGroundControl
.
multiVehicleManager
.
vehicles
anchors.fill
:
parent
delegate
:
drag.target
:
parent
VehicleMapItem
{
drag.minimumX
:
0
vehicle
:
object
drag.minimumY
:
0
coordinate
:
object
.
coordinate
drag.maximumX
:
itemDragger
.
parent
.
width
-
parent
.
width
isSatellite
:
editorMap
.
isSatelliteMap
drag.maximumY
:
itemDragger
.
parent
.
height
-
parent
.
height
size
:
ScreenTools
.
defaultFontPixelHeight
*
3
z
:
QGroundControl
.
zOrderMapItems
-
1
}
}
}
}
// Plan Element selector (Mission/Fence/Rally)
// Add the mission item visuals to the map
Row
{
Repeater
{
id
:
planElementSelectorRow
model
:
missionController
.
visualItems
anchors.top
:
toolStrip
.
top
anchors.leftMargin
:
parent
.
width
-
_rightPanelWidth
anchors.left
:
parent
.
left
z
:
QGroundControl
.
zOrderWidgets
spacing
:
_horizontalMargin
visible
:
false
// WIP: Temporarily remove - QGroundControl.corePlugin.options.enablePlanViewSelector
readonly
property
real
_buttonRadius
:
ScreenTools
.
defaultFontPixelHeight
*
0.75
ExclusiveGroup
{
id
:
planElementSelectorGroup
onCurrentChanged
:
{
switch
(
current
)
{
case
planElementMission
:
_editingLayer
=
_layerMission
_syncDropDownController
=
missionController
break
case
planElementGeoFence
:
_editingLayer
=
_layerGeoFence
_syncDropDownController
=
geoFenceController
break
case
planElementRallyPoints
:
_editingLayer
=
_layerRallyPoints
_syncDropDownController
=
rallyPointController
break
}
_syncDropDownController
.
fitViewportToItems
()
}
}
QGCRadioButton
{
id
:
planElementMission
exclusiveGroup
:
planElementSelectorGroup
text
:
qsTr
(
"
Mission
"
)
checked
:
true
color
:
mapPal
.
text
textStyle
:
Text
.
Outline
textStyleColor
:
mapPal
.
textOutline
}
Item
{
height
:
1
;
width
:
1
}
QGCRadioButton
{
id
:
planElementGeoFence
exclusiveGroup
:
planElementSelectorGroup
text
:
qsTr
(
"
Fence
"
)
color
:
mapPal
.
text
textStyle
:
Text
.
Outline
textStyleColor
:
mapPal
.
textOutline
}
Item
{
height
:
1
;
width
:
1
}
QGCRadioButton
{
id
:
planElementRallyPoints
exclusiveGroup
:
planElementSelectorGroup
text
:
qsTr
(
"
Rally
"
)
color
:
mapPal
.
text
textStyle
:
Text
.
Outline
textStyleColor
:
mapPal
.
textOutline
}
}
// Row - Plan Element Selector
// Mission Item Editor
Item
{
id
:
missionItemEditor
anchors.topMargin
:
planElementSelectorRow
.
visible
?
_margin
:
0
anchors.top
:
planElementSelectorRow
.
visible
?
planElementSelectorRow
.
bottom
:
planElementSelectorRow
.
top
anchors.bottom
:
parent
.
bottom
anchors.right
:
parent
.
right
width
:
_rightPanelWidth
opacity
:
_rightPanelOpacity
z
:
QGroundControl
.
zOrderTopMost
visible
:
_editingLayer
==
_layerMission
MouseArea
{
// This MouseArea prevents the Map below it from getting Mouse events. Without this
// things like mousewheel will scroll the Flickable and then scroll the map as well.
anchors.fill
:
missionItemEditorListView
onWheel
:
wheel
.
accepted
=
true
}
QGCListView
{
id
:
missionItemEditorListView
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.top
:
parent
.
top
height
:
parent
.
height
spacing
:
_margin
/
2
orientation
:
ListView
.
Vertical
model
:
missionController
.
visualItems
cacheBuffer
:
Math
.
max
(
height
*
2
,
0
)
clip
:
true
currentIndex
:
_currentMissionIndex
highlightMoveDuration
:
250
delegate
:
MissionItemEditor
{
map
:
editorMap
missionItem
:
object
width
:
parent
.
width
readOnly
:
false
onClicked
:
setCurrentItem
(
object
.
sequenceNumber
)
onRemove
:
{
var
removeIndex
=
index
itemDragger
.
clearItem
()
missionController
.
removeMissionItem
(
removeIndex
)
if
(
removeIndex
>=
missionController
.
visualItems
.
count
)
{
removeIndex
--
}
setCurrentItem
(
removeIndex
)
}
onInsert
:
insertSimpleMissionItem
(
editorMap
.
center
,
index
)
}
}
// QGCListView
}
// Item - Mission Item editor
// GeoFence Editor
Loader
{
anchors.topMargin
:
_margin
anchors.top
:
planElementSelectorRow
.
bottom
anchors.right
:
parent
.
right
opacity
:
_rightPanelOpacity
z
:
QGroundControl
.
zOrderWidgets
sourceComponent
:
_editingLayer
==
_layerGeoFence
?
geoFenceEditorComponent
:
undefined
property
real
availableWidth
:
_rightPanelWidth
property
real
availableHeight
:
ScreenTools
.
availableHeight
property
var
myGeoFenceController
:
geoFenceController
}
GeoFenceMapVisuals
{
delegate
:
MissionItemMapVisual
{
map
:
editorMap
map
:
editorMap
myGeoFenceController
:
geoFenceController
onClicked
:
setCurrentItem
(
sequenceNumber
)
interactive
:
_editingLayer
==
_layerGeoFence
homePosition
:
missionController
.
plannedHomePosition
planView
:
true
}
}
}
// Rally Point Editor
// Add lines between waypoints
MissionLineView
{
RallyPointEditorHeader
{
model
:
_editingLayer
==
_layerMission
?
missionController
.
waypointLines
:
undefined
id
:
rallyPointHeader
}
anchors.topMargin
:
_margin
anchors.top
:
planElementSelectorRow
.
bottom
anchors.right
:
parent
.
right
width
:
_rightPanelWidth
opacity
:
_rightPanelOpacity
z
:
QGroundControl
.
zOrderTopMost
visible
:
_editingLayer
==
_layerRallyPoints
controller
:
rallyPointController
}
RallyPointItemEditor
{
// Add the vehicles to the map
id
:
rallyPointEditor
MapItemView
{
anchors.topMargin
:
_margin
model
:
QGroundControl
.
multiVehicleManager
.
vehicles
anchors.top
:
rallyPointHeader
.
bottom
delegate
:
anchors.right
:
parent
.
right
VehicleMapItem
{
width
:
_rightPanelWidth
vehicle
:
object
opacity
:
_rightPanelOpacity
coordinate
:
object
.
coordinate
z
:
QGroundControl
.
zOrderTopMost
isSatellite
:
editorMap
.
isSatelliteMap
visible
:
_editingLayer
==
_layerRallyPoints
&&
rallyPointController
.
points
.
count
size
:
ScreenTools
.
defaultFontPixelHeight
*
3
rallyPoint
:
rallyPointController
.
currentRallyPoint
z
:
QGroundControl
.
zOrderMapItems
-
1
controller
:
rallyPointController
}
}
}
GeoFenceMapVisuals
{
map
:
editorMap
myGeoFenceController
:
geoFenceController
interactive
:
_editingLayer
==
_layerGeoFence
homePosition
:
missionController
.
plannedHomePosition
planView
:
true
}
// Rally points on map
// Rally points on map
MapItemView
{
MapItemView
{
model
:
rallyPointController
.
points
model
:
rallyPointController
.
points
delegate
:
MapQuickItem
{
delegate
:
MapQuickItem
{
id
:
itemIndicator
id
:
itemIndicator
anchorPoint.x
:
sourceItem
.
anchorPointX
anchorPoint.x
:
sourceItem
.
anchorPointX
anchorPoint.y
:
sourceItem
.
anchorPointY
anchorPoint.y
:
sourceItem
.
anchorPointY
coordinate
:
object
.
coordinate
coordinate
:
object
.
coordinate
z
:
QGroundControl
.
zOrderMapItems
z
:
QGroundControl
.
zOrderMapItems
sourceItem
:
MissionItemIndexLabel
{
sourceItem
:
MissionItemIndexLabel
{
id
:
itemIndexLabel
id
:
itemIndexLabel
label
:
qsTr
(
"
R
"
,
"
rally point map item label
"
)
label
:
qsTr
(
"
R
"
,
"
rally point map item label
"
)
checked
:
_editingLayer
==
_layerRallyPoints
?
object
==
rallyPointController
.
currentRallyPoint
:
false
checked
:
_editingLayer
==
_layerRallyPoints
?
object
==
rallyPointController
.
currentRallyPoint
:
false
onClicked
:
rallyPointController
.
currentRallyPoint
=
object
onClicked
:
rallyPointController
.
currentRallyPoint
=
object
onCheckedChanged
:
{
onCheckedChanged
:
{
if
(
checked
)
{
if
(
checked
)
{
// Setup our drag item
// Setup our drag item
itemDragger
.
visible
=
true
itemDragger
.
visible
=
true
itemDragger
.
coordinateItem
=
Qt
.
binding
(
function
()
{
return
object
})
itemDragger
.
coordinateItem
=
Qt
.
binding
(
function
()
{
return
object
})
itemDragger
.
mapCoordinateIndicator
=
Qt
.
binding
(
function
()
{
return
itemIndicator
})
itemDragger
.
mapCoordinateIndicator
=
Qt
.
binding
(
function
()
{
return
itemIndicator
})
}
}
}
}
}
}
}
}
}
}
ToolStrip
{
ToolStrip
{
id
:
toolStrip
id
:
toolStrip
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelWidth
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelWidth
anchors.left
:
parent
.
left
anchors.left
:
parent
.
left
anchors.topMargin
:
_toolButtonTopMargin
anchors.topMargin
:
_toolButtonTopMargin
anchors.top
:
parent
.
top
anchors.top
:
parent
.
top
color
:
qgcPal
.
window
color
:
qgcPal
.
window
title
:
qsTr
(
"
Plan
"
)
title
:
qsTr
(
"
Plan
"
)
z
:
QGroundControl
.
zOrderWidgets
z
:
QGroundControl
.
zOrderWidgets
buttonEnabled
:
[
true
,
true
,
true
,
true
,
true
]
buttonEnabled
:
[
true
,
true
,
true
,
true
,
true
]
buttonVisible
:
[
true
,
true
,
true
,
_showZoom
,
_showZoom
]
buttonVisible
:
[
true
,
true
,
true
,
_showZoom
,
_showZoom
]
maxHeight
:
mapScale
.
y
-
toolStrip
.
y
maxHeight
:
mapScale
.
y
-
toolStrip
.
y
property
bool
_showZoom
:
!
ScreenTools
.
isMobile
property
bool
_showZoom
:
!
ScreenTools
.
isMobile
property
bool
mySingleComplexItem
:
_singleComplexItem
property
bool
mySingleComplexItem
:
_singleComplexItem
model
:
[
model
:
[
{
{
name
:
"
Waypoint
"
,
name
:
"
Waypoint
"
,
iconSource
:
"
/qmlimages/MapAddMission.svg
"
,
iconSource
:
"
/qmlimages/MapAddMission.svg
"
,
toggle
:
true
toggle
:
true
},
},
{
{
name
:
"
Pattern
"
,
name
:
"
Pattern
"
,
iconSource
:
"
/qmlimages/MapDrawShape.svg
"
,
iconSource
:
"
/qmlimages/MapDrawShape.svg
"
,
dropPanelComponent
:
_singleComplexItem
?
undefined
:
patternDropPanel
dropPanelComponent
:
_singleComplexItem
?
undefined
:
patternDropPanel
},
},
{
{
name
:
"
Center
"
,
name
:
"
Center
"
,
iconSource
:
"
/qmlimages/MapCenter.svg
"
,
iconSource
:
"
/qmlimages/MapCenter.svg
"
,
dropPanelComponent
:
centerMapDropPanel
dropPanelComponent
:
centerMapDropPanel
},
},
{
{
name
:
"
In
"
,
name
:
"
In
"
,
iconSource
:
"
/qmlimages/ZoomPlus.svg
"
iconSource
:
"
/qmlimages/ZoomPlus.svg
"
},
},
{
{
name
:
"
Out
"
,
name
:
"
Out
"
,
iconSource
:
"
/qmlimages/ZoomMinus.svg
"
iconSource
:
"
/qmlimages/ZoomMinus.svg
"
}
]
onClicked
:
{
switch
(
index
)
{
case
0
:
_addWaypointOnClick
=
checked
break
case
1
:
if
(
_singleComplexItem
)
{
addComplexItem
(
missionController
.
complexMissionItemNames
[
0
])
}
}
]
break
case
3
:
editorMap
.
zoomLevel
+=
0.5
break
case
4
:
editorMap
.
zoomLevel
-=
0.5
break
}
}
}
onClicked
:
{
MapScale
{
switch
(
index
)
{
id
:
mapScale
case
0
:
anchors.margins
:
ScreenTools
.
defaultFontPixelHeight
*
(
0.66
)
_addWaypointOnClick
=
checked
anchors.bottom
:
waypointValuesDisplay
.
visible
?
waypointValuesDisplay
.
top
:
parent
.
bottom
break
anchors.left
:
parent
.
left
case
1
:
mapControl
:
editorMap
if
(
_singleComplexItem
)
{
visible
:
!
ScreenTools
.
isTinyScreen
addComplexItem
(
missionController
.
complexMissionItemNames
[
0
])
}
}
MissionItemStatus
{
id
:
waypointValuesDisplay
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
anchors.left
:
parent
.
left
anchors.bottom
:
parent
.
bottom
z
:
QGroundControl
.
zOrderTopMost
currentMissionItem
:
_currentMissionItem
missionItems
:
missionController
.
visualItems
expandedWidth
:
missionItemEditor
.
x
-
(
ScreenTools
.
defaultFontPixelWidth
*
2
)
missionDistance
:
missionController
.
missionDistance
missionTime
:
missionController
.
missionTime
missionMaxTelemetry
:
missionController
.
missionMaxTelemetry
visible
:
_editingLayer
==
_layerMission
&&
!
ScreenTools
.
isShortScreen
}
}
// FlightMap
// Right pane for mission editing controls
Rectangle
{
id
:
rightPanel
anchors.top
:
parent
.
top
anchors.bottom
:
parent
.
bottom
anchors.right
:
parent
.
right
width
:
_rightPanelWidth
color
:
qgcPal
.
window
opacity
:
0.95
// Plan Element selector (Mission/Fence/Rally)
Row
{
id
:
planElementSelectorRow
anchors.top
:
parent
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_horizontalMargin
visible
:
false
// WIP: Temporarily remove - QGroundControl.corePlugin.options.enablePlanViewSelector
readonly
property
real
_buttonRadius
:
ScreenTools
.
defaultFontPixelHeight
*
0.75
ExclusiveGroup
{
id
:
planElementSelectorGroup
onCurrentChanged
:
{
switch
(
current
)
{
case
planElementMission
:
_editingLayer
=
_layerMission
_syncDropDownController
=
missionController
break
break
case
3
:
case
planElementGeoFence
:
editorMap
.
zoomLevel
+=
0.5
_editingLayer
=
_layerGeoFence
_syncDropDownController
=
geoFenceController
break
break
case
4
:
case
planElementRallyPoints
:
editorMap
.
zoomLevel
-=
0.5
_editingLayer
=
_layerRallyPoints
_syncDropDownController
=
rallyPointController
break
break
}
}
_syncDropDownController
.
fitViewportToItems
()
}
}
}
}
MapScale
{
QGCRadioButton
{
id
:
mapScale
id
:
planElementMission
anchors.margins
:
ScreenTools
.
defaultFontPixelHeight
*
(
0.66
)
exclusiveGroup
:
planElementSelectorGroup
anchors.bottom
:
waypointValuesDisplay
.
visible
?
waypointValuesDisplay
.
top
:
parent
.
bottom
text
:
qsTr
(
"
Mission
"
)
anchors.left
:
parent
.
left
checked
:
true
mapControl
:
editorMap
color
:
mapPal
.
text
visible
:
!
ScreenTools
.
isTinyScreen
textStyle
:
Text
.
Outline
textStyleColor
:
mapPal
.
textOutline
}
}
MissionItemStatus
{
Item
{
height
:
1
;
width
:
1
}
id
:
waypointValuesDisplay
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
QGCRadioButton
{
anchors.left
:
parent
.
left
id
:
planElementGeoFence
anchors.bottom
:
parent
.
bottom
exclusiveGroup
:
planElementSelectorGroup
z
:
QGroundControl
.
zOrderTopMost
text
:
qsTr
(
"
Fence
"
)
currentMissionItem
:
_currentMissionItem
color
:
mapPal
.
text
missionItems
:
missionController
.
visualItems
textStyle
:
Text
.
Outline
expandedWidth
:
missionItemEditor
.
x
-
(
ScreenTools
.
defaultFontPixelWidth
*
2
)
textStyleColor
:
mapPal
.
textOutline
missionDistance
:
missionController
.
missionDistance
missionTime
:
missionController
.
missionTime
missionMaxTelemetry
:
missionController
.
missionMaxTelemetry
visible
:
_editingLayer
==
_layerMission
&&
!
ScreenTools
.
isShortScreen
}
}
}
// FlightMap
}
// Item - split view container
Item
{
height
:
1
;
width
:
1
}
QGCRadioButton
{
id
:
planElementRallyPoints
exclusiveGroup
:
planElementSelectorGroup
text
:
qsTr
(
"
Rally
"
)
color
:
mapPal
.
text
textStyle
:
Text
.
Outline
textStyleColor
:
mapPal
.
textOutline
}
}
// Row - Plan Element Selector
// Mission Item Editor
Item
{
id
:
missionItemEditor
anchors.top
:
planElementSelectorRow
.
visible
?
planElementSelectorRow
.
bottom
:
planElementSelectorRow
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.bottom
:
parent
.
bottom
visible
:
_editingLayer
==
_layerMission
QGCListView
{
id
:
missionItemEditorListView
anchors.fill
:
parent
spacing
:
_margin
/
2
orientation
:
ListView
.
Vertical
model
:
missionController
.
visualItems
cacheBuffer
:
Math
.
max
(
height
*
2
,
0
)
clip
:
true
currentIndex
:
_currentMissionIndex
highlightMoveDuration
:
250
delegate
:
MissionItemEditor
{
map
:
editorMap
missionItem
:
object
width
:
parent
.
width
readOnly
:
false
rootQgcView
:
_qgcView
onClicked
:
setCurrentItem
(
object
.
sequenceNumber
)
onRemove
:
{
var
removeIndex
=
index
itemDragger
.
clearItem
()
missionController
.
removeMissionItem
(
removeIndex
)
if
(
removeIndex
>=
missionController
.
visualItems
.
count
)
{
removeIndex
--
}
setCurrentItem
(
removeIndex
)
}
onInsert
:
insertSimpleMissionItem
(
editorMap
.
center
,
index
)
}
}
// QGCListView
}
// Item - Mission Item editor
// GeoFence Editor
Loader
{
anchors.top
:
planElementSelectorRow
.
visible
?
planElementSelectorRow
.
bottom
:
planElementSelectorRow
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
sourceComponent
:
_editingLayer
==
_layerGeoFence
?
geoFenceEditorComponent
:
undefined
property
real
availableWidth
:
_rightPanelWidth
property
real
availableHeight
:
ScreenTools
.
availableHeight
property
var
myGeoFenceController
:
geoFenceController
}
// Rally Point Editor
RallyPointEditorHeader
{
id
:
rallyPointHeader
anchors.top
:
planElementSelectorRow
.
visible
?
planElementSelectorRow
.
bottom
:
planElementSelectorRow
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
visible
:
_editingLayer
==
_layerRallyPoints
controller
:
rallyPointController
}
RallyPointItemEditor
{
id
:
rallyPointEditor
anchors.top
:
planElementSelectorRow
.
visible
?
planElementSelectorRow
.
bottom
:
planElementSelectorRow
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
visible
:
_editingLayer
==
_layerRallyPoints
&&
rallyPointController
.
points
.
count
rallyPoint
:
rallyPointController
.
currentRallyPoint
controller
:
rallyPointController
}
}
// Right panel
}
// QGCViewPanel
}
// QGCViewPanel
Component
{
Component
{
...
...
src/Settings/App.SettingsGroup.json
View file @
4544f671
...
@@ -115,6 +115,13 @@
...
@@ -115,6 +115,13 @@
"type"
:
"bool"
,
"type"
:
"bool"
,
"defaultValue"
:
false
"defaultValue"
:
false
},
},
{
"name"
:
"AutomaticMissionUpload"
,
"shortDescription"
:
"Automatic mission upload"
,
"longDescription"
:
"Automatically upload mission to vehicle after changes"
,
"type"
:
"bool"
,
"defaultValue"
:
true
},
{
{
"name"
:
"SavePath"
,
"name"
:
"SavePath"
,
"shortDescription"
:
"Application save directory"
,
"shortDescription"
:
"Application save directory"
,
...
...
src/Settings/AppSettings.cc
View file @
4544f671
...
@@ -31,6 +31,7 @@ const char* AppSettings::indoorPaletteName = "StyleIs
...
@@ -31,6 +31,7 @@ const char* AppSettings::indoorPaletteName = "StyleIs
const
char
*
AppSettings
::
showLargeCompassName
=
"ShowLargeCompass"
;
const
char
*
AppSettings
::
showLargeCompassName
=
"ShowLargeCompass"
;
const
char
*
AppSettings
::
savePathName
=
"SavePath"
;
const
char
*
AppSettings
::
savePathName
=
"SavePath"
;
const
char
*
AppSettings
::
autoLoadMissionsName
=
"AutoLoadMissions"
;
const
char
*
AppSettings
::
autoLoadMissionsName
=
"AutoLoadMissions"
;
const
char
*
AppSettings
::
automaticMissionUploadName
=
"AutomaticMissionUpload"
;
const
char
*
AppSettings
::
parameterFileExtension
=
"params"
;
const
char
*
AppSettings
::
parameterFileExtension
=
"params"
;
const
char
*
AppSettings
::
missionFileExtension
=
"mission"
;
const
char
*
AppSettings
::
missionFileExtension
=
"mission"
;
...
@@ -59,6 +60,7 @@ AppSettings::AppSettings(QObject* parent)
...
@@ -59,6 +60,7 @@ AppSettings::AppSettings(QObject* parent)
,
_showLargeCompassFact
(
NULL
)
,
_showLargeCompassFact
(
NULL
)
,
_savePathFact
(
NULL
)
,
_savePathFact
(
NULL
)
,
_autoLoadMissionsFact
(
NULL
)
,
_autoLoadMissionsFact
(
NULL
)
,
_automaticMissionUpload
(
NULL
)
{
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
qmlRegisterUncreatableType
<
AppSettings
>
(
"QGroundControl.SettingsManager"
,
1
,
0
,
"AppSettings"
,
"Reference only"
);
qmlRegisterUncreatableType
<
AppSettings
>
(
"QGroundControl.SettingsManager"
,
1
,
0
,
"AppSettings"
,
"Reference only"
);
...
@@ -276,3 +278,12 @@ Fact* AppSettings::autoLoadMissions(void)
...
@@ -276,3 +278,12 @@ Fact* AppSettings::autoLoadMissions(void)
return
_autoLoadMissionsFact
;
return
_autoLoadMissionsFact
;
}
}
Fact
*
AppSettings
::
automaticMissionUpload
(
void
)
{
if
(
!
_automaticMissionUpload
)
{
_automaticMissionUpload
=
_createSettingsFact
(
automaticMissionUploadName
);
}
return
_automaticMissionUpload
;
}
src/Settings/AppSettings.h
View file @
4544f671
...
@@ -34,6 +34,7 @@ public:
...
@@ -34,6 +34,7 @@ public:
Q_PROPERTY
(
Fact
*
showLargeCompass
READ
showLargeCompass
CONSTANT
)
Q_PROPERTY
(
Fact
*
showLargeCompass
READ
showLargeCompass
CONSTANT
)
Q_PROPERTY
(
Fact
*
savePath
READ
savePath
CONSTANT
)
Q_PROPERTY
(
Fact
*
savePath
READ
savePath
CONSTANT
)
Q_PROPERTY
(
Fact
*
autoLoadMissions
READ
autoLoadMissions
CONSTANT
)
Q_PROPERTY
(
Fact
*
autoLoadMissions
READ
autoLoadMissions
CONSTANT
)
Q_PROPERTY
(
Fact
*
automaticMissionUpload
READ
automaticMissionUpload
CONSTANT
)
Q_PROPERTY
(
QString
missionSavePath
READ
missionSavePath
NOTIFY
savePathsChanged
)
Q_PROPERTY
(
QString
missionSavePath
READ
missionSavePath
NOTIFY
savePathsChanged
)
Q_PROPERTY
(
QString
parameterSavePath
READ
parameterSavePath
NOTIFY
savePathsChanged
)
Q_PROPERTY
(
QString
parameterSavePath
READ
parameterSavePath
NOTIFY
savePathsChanged
)
...
@@ -58,6 +59,7 @@ public:
...
@@ -58,6 +59,7 @@ public:
Fact
*
showLargeCompass
(
void
);
Fact
*
showLargeCompass
(
void
);
Fact
*
savePath
(
void
);
Fact
*
savePath
(
void
);
Fact
*
autoLoadMissions
(
void
);
Fact
*
autoLoadMissions
(
void
);
Fact
*
automaticMissionUpload
(
void
);
QString
missionSavePath
(
void
);
QString
missionSavePath
(
void
);
QString
parameterSavePath
(
void
);
QString
parameterSavePath
(
void
);
...
@@ -80,6 +82,7 @@ public:
...
@@ -80,6 +82,7 @@ public:
static
const
char
*
showLargeCompassName
;
static
const
char
*
showLargeCompassName
;
static
const
char
*
savePathName
;
static
const
char
*
savePathName
;
static
const
char
*
autoLoadMissionsName
;
static
const
char
*
autoLoadMissionsName
;
static
const
char
*
automaticMissionUploadName
;
// Application wide file extensions
// Application wide file extensions
static
const
char
*
parameterFileExtension
;
static
const
char
*
parameterFileExtension
;
...
@@ -116,6 +119,7 @@ private:
...
@@ -116,6 +119,7 @@ private:
SettingsFact
*
_showLargeCompassFact
;
SettingsFact
*
_showLargeCompassFact
;
SettingsFact
*
_savePathFact
;
SettingsFact
*
_savePathFact
;
SettingsFact
*
_autoLoadMissionsFact
;
SettingsFact
*
_autoLoadMissionsFact
;
SettingsFact
*
_automaticMissionUpload
;
};
};
#endif
#endif
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