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
e39f6f28
Commit
e39f6f28
authored
Mar 28, 2017
by
Don Gagne
Committed by
GitHub
Mar 28, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4877 from DonLakeFlyer/PlanAgain
Change Plan sync model yet again
parents
d5e12680
d95ec754
Changes
10
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
154 additions
and
329 deletions
+154
-329
MissionController.cc
src/MissionManager/MissionController.cc
+12
-66
MissionController.h
src/MissionManager/MissionController.h
+1
-12
MissionSettings.FactMetaData.json
src/MissionManager/MissionSettings.FactMetaData.json
+0
-6
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+2
-23
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+0
-16
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+10
-1
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+1
-0
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+1
-139
PlanToolBar.qml
src/PlanView/PlanToolBar.qml
+5
-4
PlanView.qml
src/PlanView/PlanView.qml
+122
-62
No files found.
src/MissionManager/MissionController.cc
View file @
e39f6f28
...
...
@@ -647,30 +647,6 @@ void MissionController::loadFromFile(const QString& filename)
MissionController
::
_scanForAdditionalSettings
(
_visualItems
,
_activeVehicle
);
_initAllVisualItems
();
// Split the filename into directory and filename
QString
filenameOnly
=
filename
;
int
lastSepIndex
=
filename
.
lastIndexOf
(
QStringLiteral
(
"/"
));
if
(
lastSepIndex
!=
-
1
)
{
filenameOnly
=
filename
.
right
(
filename
.
length
()
-
lastSepIndex
-
1
);
}
QString
directoryOnly
=
filename
.
left
(
filename
.
length
()
-
filenameOnly
.
length
()
-
1
);
QString
extension
=
AppSettings
::
missionFileExtension
;
if
(
filenameOnly
.
endsWith
(
"."
+
extension
))
{
filenameOnly
=
filenameOnly
.
left
(
filenameOnly
.
length
()
-
extension
.
length
()
-
1
);
}
_settingsItem
->
missionName
()
->
setRawValue
(
filenameOnly
);
if
(
directoryOnly
==
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
missionSavePath
())
{
QString
emptyString
;
_settingsItem
->
setLoadedMissionDirectory
(
emptyString
);
}
else
{
_settingsItem
->
setLoadedMissionDirectory
(
directoryOnly
);
}
_settingsItem
->
setExistingMission
(
true
);
sendToVehicle
();
}
...
...
@@ -1235,7 +1211,7 @@ void MissionController::_initAllVisualItems(void)
_recalcAll
();
connect
(
_visualItems
,
&
QmlObjectListModel
::
dirtyChanged
,
this
,
&
MissionController
::
d
irtyChanged
);
connect
(
_visualItems
,
&
QmlObjectListModel
::
dirtyChanged
,
this
,
&
MissionController
::
_visualItemsD
irtyChanged
);
connect
(
_visualItems
,
&
QmlObjectListModel
::
countChanged
,
this
,
&
MissionController
::
_updateContainsItems
);
emit
visualItemsChanged
();
...
...
@@ -1250,7 +1226,7 @@ void MissionController::_deinitAllVisualItems(void)
_deinitVisualItem
(
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
)));
}
disconnect
(
_visualItems
,
&
QmlObjectListModel
::
dirtyChanged
,
this
,
&
MissionController
::
d
irtyChanged
);
disconnect
(
_visualItems
,
&
QmlObjectListModel
::
dirtyChanged
,
this
,
&
MissionController
::
_visualItemsD
irtyChanged
);
disconnect
(
_visualItems
,
&
QmlObjectListModel
::
countChanged
,
this
,
&
MissionController
::
_updateContainsItems
);
}
...
...
@@ -1605,46 +1581,16 @@ bool MissionController::missionInProgress(void) const
return
_visualItems
&&
_visualItems
->
count
()
>
1
&&
(
!
_visualItems
->
value
<
VisualMissionItem
*>
(
0
)
->
isCurrentItem
()
&&
!
_visualItems
->
value
<
VisualMissionItem
*>
(
1
)
->
isCurrentItem
());
}
void
MissionController
::
save
(
void
)
{
// Save to file if the mission is named
QString
missionDir
=
_settingsItem
->
loadedMissionDirectory
();
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
);
}
_settingsItem
->
setExistingMission
(
savedToFile
);
}
void
MissionController
::
saveAndSend
(
void
)
void
MissionController
::
_visualItemsDirtyChanged
(
bool
dirty
)
{
// Send to vehicle if we are connected
if
(
!
_activeVehicle
->
isOfflineEditingVehicle
())
{
sendToVehicle
();
if
(
dirty
)
{
if
(
_visualItems
->
count
()
>
1
)
{
emit
dirtyChanged
(
true
);
}
else
{
// This was a change to mission settings with no other mission items added
_visualItems
->
setDirty
(
false
);
}
}
else
{
emit
dirtyChanged
(
false
);
}
}
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
();
}
src/MissionManager/MissionController.h
View file @
e39f6f28
...
...
@@ -89,18 +89,6 @@ public:
/// Sends the mission items to the specified vehicle
static
void
sendItemsToVehicle
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualMissionItems
);
/// Saves the mission to file
Q_INVOKABLE
void
save
(
void
);
/// Save and to file and send to vehicle if possible
Q_INVOKABLE
void
saveAndSend
(
void
);
/// Removes all items from the mission
Q_INVOKABLE
void
clearMission
(
void
);
/// Closes the mission, saving and sending as needed before closing
Q_INVOKABLE
void
closeMission
(
void
);
// Overrides from PlanElementController
void
start
(
bool
editMode
)
final
;
void
startStaticActiveVehicle
(
Vehicle
*
vehicle
)
final
;
...
...
@@ -155,6 +143,7 @@ private slots:
void
_recalcWaypointLines
(
void
);
void
_recalcMissionFlightStatus
(
void
);
void
_updateContainsItems
(
void
);
void
_visualItemsDirtyChanged
(
bool
dirty
);
private:
void
_init
(
void
);
...
...
src/MissionManager/MissionSettings.FactMetaData.json
View file @
e39f6f28
...
...
@@ -22,11 +22,5 @@
"enumStrings"
:
"No action on mission end,Loiter after mission end,RTL after mission end"
,
"enumValues"
:
"0,1,2"
,
"defaultValue"
:
0
},
{
"name"
:
"MissionName"
,
"shortDescription"
:
"Name for the mission."
,
"type"
:
"string"
,
"defaultValue"
:
""
}
]
src/MissionManager/MissionSettingsItem.cc
View file @
e39f6f28
...
...
@@ -23,7 +23,6 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL
const
char
*
MissionSettingsItem
::
jsonComplexItemTypeValue
=
"MissionSettings"
;
const
char
*
MissionSettingsItem
::
_missionNameName
=
"MissionName"
;
const
char
*
MissionSettingsItem
::
_plannedHomePositionAltitudeName
=
"PlannedHomePositionAltitude"
;
const
char
*
MissionSettingsItem
::
_missionFlightSpeedName
=
"FlightSpeed"
;
const
char
*
MissionSettingsItem
::
_missionEndActionName
=
"MissionEndAction"
;
...
...
@@ -32,9 +31,7 @@ QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
MissionSettingsItem
::
MissionSettingsItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
,
_existingMission
(
false
)
,
_specifyMissionFlightSpeed
(
false
)
,
_missionNameFact
(
0
,
_missionNameName
,
FactMetaData
::
valueTypeString
)
,
_plannedHomePositionAltitudeFact
(
0
,
_plannedHomePositionAltitudeName
,
FactMetaData
::
valueTypeDouble
)
,
_missionFlightSpeedFact
(
0
,
_missionFlightSpeedName
,
FactMetaData
::
valueTypeDouble
)
,
_missionEndActionFact
(
0
,
_missionEndActionName
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -47,12 +44,10 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/MissionSettings.FactMetaData.json"
),
NULL
/* metaDataParent */
);
}
_missionNameFact
.
setMetaData
(
_metaDataMap
[
_missionNameName
]);
_plannedHomePositionAltitudeFact
.
setMetaData
(
_metaDataMap
[
_plannedHomePositionAltitudeName
]);
_missionFlightSpeedFact
.
setMetaData
(
_metaDataMap
[
_missionFlightSpeedName
]);
_missionEndActionFact
.
setMetaData
(
_metaDataMap
[
_missionEndActionName
]);
_missionNameFact
.
setRawValue
(
_missionNameFact
.
rawDefaultValue
());
_plannedHomePositionAltitudeFact
.
setRawValue
(
_plannedHomePositionAltitudeFact
.
rawDefaultValue
());
_missionEndActionFact
.
setRawValue
(
_missionEndActionFact
.
rawDefaultValue
());
...
...
@@ -63,8 +58,8 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
setHomePositionSpecialCase
(
true
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_plannedHomePositionAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_setDirty
);
connect
(
&
_plannedHomePositionAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_updateAltitudeInCoordinate
);
...
...
@@ -411,19 +406,3 @@ void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
emit
exitCoordinateChanged
(
_plannedHomePositionCoordinate
);
}
}
void
MissionSettingsItem
::
setExistingMission
(
bool
existingMission
)
{
if
(
existingMission
!=
_existingMission
)
{
_existingMission
=
existingMission
;
emit
existingMissionChanged
(
existingMission
);
}
}
void
MissionSettingsItem
::
setLoadedMissionDirectory
(
QString
&
loadedMissionDirectory
)
{
if
(
_loadedMissionDirectory
!=
loadedMissionDirectory
)
{
_loadedMissionDirectory
=
loadedMissionDirectory
;
emit
loadedMissionDirectoryChanged
(
loadedMissionDirectory
);
}
}
src/MissionManager/MissionSettingsItem.h
View file @
e39f6f28
...
...
@@ -32,24 +32,18 @@ public:
};
Q_ENUMS
(
MissionEndAction
)
Q_PROPERTY
(
Fact
*
missionName
READ
missionName
CONSTANT
)
Q_PROPERTY
(
QString
loadedMissionDirectory
READ
loadedMissionDirectory
WRITE
setLoadedMissionDirectory
NOTIFY
loadedMissionDirectoryChanged
)
Q_PROPERTY
(
bool
existingMission
READ
existingMission
WRITE
setExistingMission
NOTIFY
existingMissionChanged
)
Q_PROPERTY
(
bool
specifyMissionFlightSpeed
READ
specifyMissionFlightSpeed
WRITE
setSpecifyMissionFlightSpeed
NOTIFY
specifyMissionFlightSpeedChanged
)
Q_PROPERTY
(
Fact
*
missionFlightSpeed
READ
missionFlightSpeed
CONSTANT
)
Q_PROPERTY
(
Fact
*
missionEndAction
READ
missionEndAction
CONSTANT
)
Q_PROPERTY
(
Fact
*
plannedHomePositionAltitude
READ
plannedHomePositionAltitude
CONSTANT
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Fact
*
missionName
(
void
)
{
return
&
_missionNameFact
;
}
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
missionFlightSpeed
(
void
)
{
return
&
_missionFlightSpeedFact
;
}
Fact
*
missionEndAction
(
void
)
{
return
&
_missionEndActionFact
;
}
bool
specifyMissionFlightSpeed
(
void
)
const
{
return
_specifyMissionFlightSpeed
;
}
bool
existingMission
(
void
)
const
{
return
_existingMission
;
}
void
setSpecifyMissionFlightSpeed
(
bool
specifyMissionFlightSpeed
);
void
setExistingMission
(
bool
existingMission
);
QObject
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
/// Scans the loaded items for settings items
...
...
@@ -62,10 +56,6 @@ public:
/// @return true: Mission end action was added
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
double
complexDistance
(
void
)
const
final
;
...
...
@@ -104,8 +94,6 @@ public:
signals:
void
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
existingMissionChanged
(
bool
existingMission
);
void
loadedMissionDirectoryChanged
(
QString
&
loadedMissionDirectory
);
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
...
...
@@ -114,14 +102,11 @@ private slots:
void
_updateAltitudeInCoordinate
(
QVariant
value
);
private:
bool
_existingMission
;
bool
_specifyMissionFlightSpeed
;
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
Fact
_missionNameFact
;
Fact
_plannedHomePositionAltitudeFact
;
Fact
_missionFlightSpeedFact
;
Fact
_missionEndActionFact
;
QString
_loadedMissionDirectory
;
CameraSection
_cameraSection
;
int
_sequenceNumber
;
...
...
@@ -129,7 +114,6 @@ private:
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_missionNameName
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_missionFlightSpeedName
;
static
const
char
*
_missionEndActionName
;
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
e39f6f28
...
...
@@ -51,6 +51,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
:
VisualMissionItem
(
vehicle
,
parent
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -87,6 +88,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
,
_missionItem
(
missionItem
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -117,6 +119,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
,
_missionItem
(
other
.
_vehicle
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -390,6 +393,8 @@ QmlObjectListModel* SimpleMissionItem::textFieldFacts(void)
_missionItem
.
_param7Fact
.
setMetaData
(
_defaultParamMetaData
);
model
->
append
(
&
_missionItem
.
_param7Fact
);
}
else
{
_ignoreDirtyChangeSignals
=
true
;
_clearParamMetaData
();
MAV_CMD
command
;
...
...
@@ -425,6 +430,8 @@ QmlObjectListModel* SimpleMissionItem::textFieldFacts(void)
_missionItem
.
_param7Fact
.
setMetaData
(
_altitudeMetaData
);
model
->
append
(
&
_missionItem
.
_param7Fact
);
}
_ignoreDirtyChangeSignals
=
false
;
}
return
model
;
...
...
@@ -524,7 +531,9 @@ void SimpleMissionItem::setDirty(bool dirty)
void
SimpleMissionItem
::
_setDirtyFromSignal
(
void
)
{
setDirty
(
true
);
if
(
!
_ignoreDirtyChangeSignals
)
{
setDirty
(
true
);
}
}
void
SimpleMissionItem
::
_sendCoordinateChanged
(
void
)
...
...
src/MissionManager/SimpleMissionItem.h
View file @
e39f6f28
...
...
@@ -143,6 +143,7 @@ private:
MissionItem
_missionItem
;
bool
_rawEdit
;
bool
_dirty
;
bool
_ignoreDirtyChangeSignals
;
CameraSection
*
_cameraSection
;
...
...
src/PlanView/MissionSettingsEditor.qml
View file @
e39f6f28
...
...
@@ -31,10 +31,6 @@ Rectangle {
property
bool
_mobile
:
ScreenTools
.
isMobile
property
var
_savePath
:
QGroundControl
.
settingsManager
.
appSettings
.
missionSavePath
property
var
_fileExtension
:
QGroundControl
.
settingsManager
.
appSettings
.
missionFileExtension
property
bool
_newMissionAlreadyExists
:
false
property
bool
_noMissionName
:
missionItem
.
missionName
.
valueString
===
""
property
bool
_showMissionList
:
_noMissionItemsAdded
&&
(
_noMissionName
||
_newMissionAlreadyExists
)
property
bool
_existingMissionLoaded
:
missionItem
.
existingMission
property
var
_appSettings
:
QGroundControl
.
settingsManager
.
appSettings
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
...
...
@@ -43,16 +39,6 @@ Rectangle {
QGCPalette
{
id
:
qgcPal
}
QFileDialogController
{
id
:
fileController
}
Connections
{
target
:
missionItem
.
missionName
onRawValueChanged
:
{
if
(
!
_existingMissionLoaded
)
{
_newMissionAlreadyExists
=
!
_noMissionName
&&
fileController
.
fileExists
(
_savePath
+
"
/
"
+
missionItem
.
missionName
.
valueString
+
"
.
"
+
_fileExtension
)
}
}
}
Loader
{
id
:
deferedload
active
:
valuesRect
.
visible
...
...
@@ -74,140 +60,16 @@ Rectangle {
anchors.top
:
parent
.
top
spacing
:
_margin
QGCLabel
{
text
:
qsTr
(
"
Mission name
"
)
font.pointSize
:
ScreenTools
.
smallFontPointSize
}
FactTextField
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
fact
:
missionItem
.
missionName
visible
:
!
_existingMissionLoaded
}
QGCLabel
{
text
:
missionItem
.
missionName
.
valueString
visible
:
_existingMissionLoaded
}
QGCLabel
{
text
:
qsTr
(
"
Mission already exists
"
)
font.pointSize
:
ScreenTools
.
smallFontPointSize
color
:
qgcPal
.
warningText
visible
:
!
_existingMissionLoaded
&&
_newMissionAlreadyExists
}
FactCheckBox
{
id
:
automaticUploadCheckbox
text
:
qsTr
(
"
Automatically upload on exit
"
)
fact
:
_appSettings
.
automaticMissionUpload
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
QGCButton
{
text
:
qsTr
(
"
Remove All
"
)
visible
:
!
_noMissionItemsAdded
Layout.fillWidth
:
true
onClicked
:
missionController
.
clearMission
()
}
QGCButton
{
text
:
qsTr
(
"
New Mission
"
)
visible
:
!
_noMissionItemsAdded
Layout.fillWidth
:
true
onClicked
:
missionController
.
closeMission
()
}
}
Loader
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
sourceComponent
:
_showMissionList
?
missionList
:
missionSettings
sourceComponent
:
missionSettings
}
}
// Column
}
// Item
}
// Component
}
// Loader
Component
{
id
:
missionList
QGCFlickable
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
height
:
missionColumn
.
height
Column
{
id
:
missionColumn
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
SectionHeader
{
text
:
qsTr
(
"
Load Mission
"
)
showSpacer
:
false
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
QGCButton
{
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
()
}
}
}
}
QGCLabel
{
text
:
qsTr
(
"
No mission files
"
)
visible
:
missionRepeater
.
model
.
length
===
0
}
Repeater
{
id
:
missionRepeater
model
:
fileController
.
getFiles
(
_savePath
,
_fileExtension
);
QGCButton
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
text
:
modelData
onClicked
:
{
missionController
.
loadFromFile
(
fileController
.
fullyQualifiedFilename
(
_savePath
,
modelData
,
_fileExtension
))
}
}
}
}
}
}
Component
{
id
:
missionSettings
...
...
src/PlanView/PlanToolBar.qml
View file @
e39f6f28
...
...
@@ -89,7 +89,7 @@ Rectangle {
onClicked
:
{
checked
=
false
if
(
missionController
.
save
OnSwitch
())
{
if
(
missionController
.
upload
OnSwitch
())
{
showFlyView
()
}
}
...
...
@@ -178,9 +178,10 @@ Rectangle {
anchors.rightMargin
:
_margins
anchors.right
:
parent
.
right
anchors.verticalCenter
:
parent
.
verticalCenter
text
:
qsTr
(
"
Upload
"
)
visible
:
_manualUpload
&&
missionController
.
dirty
onClicked
:
missionController
.
uploadFromToolbar
()
text
:
missionController
.
dirty
?
qsTr
(
"
Upload Required
"
)
:
qsTr
(
"
Upload
"
)
enabled
:
_activeVehicle
visible
:
_manualUpload
onClicked
:
missionController
.
upload
()
}
}
src/PlanView/PlanView.qml
View file @
e39f6f28
This diff is collapsed.
Click to expand it.
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