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
08ace3c5
Commit
08ace3c5
authored
Mar 26, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
New Plan sync user model
parent
c2e3fa26
Changes
11
Expand all
Show whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
399 additions
and
278 deletions
+399
-278
MissionController.cc
src/MissionManager/MissionController.cc
+37
-0
MissionController.h
src/MissionManager/MissionController.h
+3
-0
MissionSettings.FactMetaData.json
src/MissionManager/MissionSettings.FactMetaData.json
+8
-2
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+32
-26
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+23
-10
MissionItemEditor.qml
src/PlanView/MissionItemEditor.qml
+1
-1
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+273
-162
PlanToolBar.qml
src/PlanView/PlanToolBar.qml
+3
-45
PlanView.qml
src/PlanView/PlanView.qml
+17
-31
ParameterEditorDialog.qml
src/QmlControls/ParameterEditorDialog.qml
+1
-0
QFileDialogController.cc
src/QmlControls/QFileDialogController.cc
+1
-1
No files found.
src/MissionManager/MissionController.cc
View file @
08ace3c5
...
...
@@ -646,6 +646,21 @@ void MissionController::loadFromFile(const QString& filename)
MissionController
::
_scanForAdditionalSettings
(
_visualItems
,
_activeVehicle
);
_initAllVisualItems
();
QString
filenameOnly
=
filename
;
int
lastSepIndex
=
filename
.
lastIndexOf
(
QStringLiteral
(
"/"
));
if
(
lastSepIndex
!=
-
1
)
{
filenameOnly
=
filename
.
right
(
filename
.
length
()
-
lastSepIndex
-
1
);
}
QString
extension
=
AppSettings
::
missionFileExtension
;
if
(
filenameOnly
.
endsWith
(
"."
+
extension
))
{
filenameOnly
=
filenameOnly
.
left
(
filenameOnly
.
length
()
-
extension
.
length
()
-
1
);
}
_settingsItem
->
missionName
()
->
setRawValue
(
filenameOnly
);
_settingsItem
->
setExistingMission
(
true
);
sendToVehicle
();
}
bool
MissionController
::
loadItemsFromFile
(
Vehicle
*
vehicle
,
const
QString
&
filename
,
QmlObjectListModel
**
visualItems
)
...
...
@@ -1577,3 +1592,25 @@ 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
missionFullPath
=
_settingsItem
->
missionFullPath
()
->
rawValue
().
toString
();
if
(
!
missionFullPath
.
isEmpty
())
{
saveToFile
(
missionFullPath
);
}
// Send to vehicle if we are connected
if
(
!
_activeVehicle
->
isOfflineEditingVehicle
())
{
sendToVehicle
();
}
_settingsItem
->
setExistingMission
(
_visualItems
->
count
()
>
1
&&
!
missionFullPath
.
isEmpty
());
}
void
MissionController
::
clearMission
(
void
)
{
removeAll
();
save
();
}
src/MissionManager/MissionController.h
View file @
08ace3c5
...
...
@@ -88,6 +88,9 @@ public:
/// Sends the mission items to the specified vehicle
static
void
sendItemsToVehicle
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualMissionItems
);
Q_INVOKABLE
void
save
(
void
);
Q_INVOKABLE
void
clearMission
(
void
);
// Overrides from PlanElementController
void
start
(
bool
editMode
)
final
;
void
startStaticActiveVehicle
(
Vehicle
*
vehicle
)
final
;
...
...
src/MissionManager/MissionSettings.FactMetaData.json
View file @
08ace3c5
...
...
@@ -19,8 +19,14 @@
"name"
:
"MissionEndAction"
,
"shortDescription"
:
"The action to take when the mission completed."
,
"type"
:
"uint32"
,
"enumStrings"
:
"No action on mission
completion,Loiter after mission completes,RTL after mission completes,Land after mission completes
"
,
"enumValues"
:
"0,1,2
,3
"
,
"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 @
08ace3c5
...
...
@@ -23,6 +23,8 @@ QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemL
const
char
*
MissionSettingsItem
::
jsonComplexItemTypeValue
=
"MissionSettings"
;
const
char
*
MissionSettingsItem
::
_missionNameName
=
"MissionName"
;
const
char
*
MissionSettingsItem
::
_missionFullPathName
=
"MissionFullPath"
;
const
char
*
MissionSettingsItem
::
_plannedHomePositionAltitudeName
=
"PlannedHomePositionAltitude"
;
const
char
*
MissionSettingsItem
::
_missionFlightSpeedName
=
"FlightSpeed"
;
const
char
*
MissionSettingsItem
::
_missionEndActionName
=
"MissionEndAction"
;
...
...
@@ -31,7 +33,10 @@ QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
MissionSettingsItem
::
MissionSettingsItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
ComplexMissionItem
(
vehicle
,
parent
)
,
_existingMission
(
false
)
,
_specifyMissionFlightSpeed
(
false
)
,
_missionNameFact
(
0
,
_missionNameName
,
FactMetaData
::
valueTypeString
)
,
_missionFullPathFact
(
0
,
_missionFullPathName
,
FactMetaData
::
valueTypeString
)
,
_plannedHomePositionAltitudeFact
(
0
,
_plannedHomePositionAltitudeName
,
FactMetaData
::
valueTypeDouble
)
,
_missionFlightSpeedFact
(
0
,
_missionFlightSpeedName
,
FactMetaData
::
valueTypeDouble
)
,
_missionEndActionFact
(
0
,
_missionEndActionName
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -44,10 +49,12 @@ 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
());
...
...
@@ -58,6 +65,8 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
setHomePositionSpecialCase
(
true
);
connect
(
&
_missionNameFact
,
&
Fact
::
valueChanged
,
this
,
&
MissionSettingsItem
::
_missionNameChanged
);
connect
(
this
,
&
MissionSettingsItem
::
specifyMissionFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
connect
(
&
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
MissionSettingsItem
::
_setDirtyAndUpdateLastSequenceNumber
);
...
...
@@ -232,21 +241,6 @@ bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int se
false
,
// isCurrentItem
missionItemParent
);
break
;
case
MissionEndLand
:
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Appending end action Land seqNum"
<<
seqNum
;
item
=
new
MissionItem
(
seqNum
,
MAV_CMD_NAV_LAND
,
MAV_FRAME_GLOBAL_RELATIVE_ALT
,
0
,
// abort Altitude
0
,
0
,
// not used
0
,
// yaw
lastWaypointCoord
.
latitude
(),
lastWaypointCoord
.
longitude
(),
0
,
// altitude
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
break
;
case
MissionEndRTL
:
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Appending end action RTL seqNum"
<<
seqNum
;
item
=
new
MissionItem
(
seqNum
,
...
...
@@ -351,14 +345,6 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems
}
break
;
case
MAV_CMD_NAV_LAND
:
if
(
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Scan: Found end action Land"
;
settingsItem
->
missionEndAction
()
->
setRawValue
(
MissionEndLand
);
visualItems
->
removeAt
(
lastIndex
)
->
deleteLater
();
}
break
;
case
MAV_CMD_NAV_RETURN_TO_LAUNCH
:
if
(
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
qCDebug
(
MissionSettingsComplexItemLog
)
<<
"Scan: Found end action RTL"
;
...
...
@@ -429,3 +415,23 @@ void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
emit
exitCoordinateChanged
(
_plannedHomePositionCoordinate
);
}
}
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
)
{
if
(
existingMission
!=
_existingMission
)
{
_existingMission
=
existingMission
;
emit
existingMissionChanged
(
existingMission
);
}
}
src/MissionManager/MissionSettingsItem.h
View file @
08ace3c5
...
...
@@ -28,23 +28,29 @@ public:
enum
MissionEndAction
{
MissionEndNoAction
,
MissionEndLoiter
,
MissionEndRTL
,
MissionEndLand
MissionEndRTL
};
Q_ENUMS
(
MissionEndAction
)
Q_PROPERTY
(
Fact
*
missionName
READ
missionName
CONSTANT
)
Q_PROPERTY
(
Fact
*
missionFullPath
READ
missionFullPath
CONSTANT
)
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
)
bool
specifyMissionFlightSpeed
(
void
)
const
{
return
_specifyMissionFlightSpeed
;
}
Fact
*
missionName
(
void
)
{
return
&
_missionNameFact
;
}
Fact
*
missionFullPath
(
void
)
{
return
&
_missionFullPathFact
;
}
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
...
...
@@ -94,17 +100,22 @@ public:
static
const
char
*
jsonComplexItemTypeValue
;
signals:
bool
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
specifyMissionFlightSpeedChanged
(
bool
specifyMissionFlightSpeed
);
void
existingMissionChanged
(
bool
existingMission
);
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirty
(
void
);
void
_cameraSectionDirtyChanged
(
bool
dirty
);
void
_updateAltitudeInCoordinate
(
QVariant
value
);
void
_missionNameChanged
(
QVariant
value
);
private:
bool
_existingMission
;
bool
_specifyMissionFlightSpeed
;
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
Fact
_missionNameFact
;
Fact
_missionFullPathFact
;
Fact
_plannedHomePositionAltitudeFact
;
Fact
_missionFlightSpeedFact
;
Fact
_missionEndActionFact
;
...
...
@@ -115,6 +126,8 @@ private:
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_missionNameName
;
static
const
char
*
_missionFullPathName
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_missionFlightSpeedName
;
static
const
char
*
_missionEndActionName
;
...
...
src/PlanView/MissionItemEditor.qml
View file @
08ace3c5
...
...
@@ -28,7 +28,7 @@ Rectangle {
property
bool
_currentItem
:
missionItem
.
isCurrentItem
property
color
_outerTextColor
:
_currentItem
?
"
black
"
:
qgcPal
.
text
property
bool
_noMissionItemsAdded
:
ListView
.
view
.
model
.
count
==
1
property
bool
_noMissionItemsAdded
:
ListView
.
view
.
model
.
count
==
=
1
property
real
_sectionSpacer
:
ScreenTools
.
defaultFontPixelWidth
/
2
// spacing between section headings
readonly
property
real
_editFieldWidth
:
Math
.
min
(
width
-
_margin
*
2
,
ScreenTools
.
defaultFontPixelWidth
*
12
)
...
...
src/PlanView/MissionSettingsEditor.qml
View file @
08ace3c5
This diff is collapsed.
Click to expand it.
src/PlanView/PlanToolBar.qml
View file @
08ace3c5
...
...
@@ -80,29 +80,13 @@ Rectangle {
checked
:
false
onClicked
:
{
console
.
log
(
"
Leave plan clicked
"
)
checked
=
false
if
(
missionController
.
dirty
)
{
uploadPrompt
.
visible
=
true
}
else
{
missionController
.
saveOnSwitch
()
showFlyView
()
}
}
MessageDialog
{
id
:
uploadPrompt
title
:
_activeVehicle
?
qsTr
(
"
Unsent changes
"
)
:
qsTr
(
"
Unsaved changes
"
)
text
:
qsTr
(
"
You have %1 changes to your mission. Are you sure you want to leave before you %2?
"
).
arg
(
_activeVehicle
?
qsTr
(
"
unsent
"
)
:
qsTr
(
"
unsaved
"
)).
arg
(
_activeVehicle
?
qsTr
(
"
send the mission to the vehicle
"
)
:
qsTr
(
"
save the mission to a file
"
))
standardButtons
:
StandardButton
.
Yes
|
StandardButton
.
No
onNo
:
visible
=
false
onYes
:
{
visible
=
false
showFlyView
()
}
}
}
GridLayout
{
anchors.top
:
parent
.
top
anchors.bottom
:
parent
.
bottom
...
...
@@ -180,31 +164,5 @@ Rectangle {
QGCLabel
{
text
:
"
--
"
}
}
}
QGCButton
{
anchors.rightMargin
:
_margins
anchors.right
:
parent
.
right
anchors.verticalCenter
:
parent
.
verticalCenter
text
:
_activeVehicle
?
qsTr
(
"
Upload
"
)
:
qsTr
(
"
Save
"
)
visible
:
missionDirty
primary
:
true
onClicked
:
{
if
(
_activeVehicle
)
{
missionController
.
sendToVehicle
()
}
else
{
missionController
.
saveToSelectedFile
()
}
}
NumberAnimation
on
opacity
{
id
:
opacityAnimation
running
:
missionDirty
from
:
0.5
to
:
1.0
loops
:
Animation
.
Infinite
duration
:
2000
}
}
}
src/PlanView/PlanView.qml
View file @
08ace3c5
...
...
@@ -103,15 +103,16 @@ QGCView {
setCurrentItem
(
0
)
}
// Users is switching away from Plan View
function
saveOnSwitch
()
{
save
()
}
function
loadFromSelectedFile
()
{
fileDialog
.
title
=
qsTr
(
"
Select Mission File
"
)
fileDialog
.
selectExisting
=
true
fileDialog
.
nameFilters
=
missionController
.
nameFilters
fileDialog
.
openForLoad
()
// FIXME: Hmm
//mapFitFunctions.fitMapViewportToMissionItems()
//_currentMissionItem = _visualItems.get(0)
}
function
saveToSelectedFile
()
{
...
...
@@ -464,13 +465,12 @@ QGCView {
// Plan Element selector (Mission/Fence/Rally)
Row
{
id
:
planElementSelectorRow
anchors.topMargin
:
parent
.
height
-
ScreenTools
.
availableHeight
+
_margin
anchors.top
:
parent
.
top
anchors.top
:
toolStrip
.
top
anchors.leftMargin
:
parent
.
width
-
_rightPanelWidth
anchors.left
:
parent
.
left
z
:
QGroundControl
.
zOrderWidgets
spacing
:
_horizontalMargin
visible
:
QGroundControl
.
corePlugin
.
options
.
enablePlanViewSelector
visible
:
false
// WIP: Temporarily remove -
QGroundControl.corePlugin.options.enablePlanViewSelector
readonly
property
real
_buttonRadius
:
ScreenTools
.
defaultFontPixelHeight
*
0.75
...
...
@@ -531,7 +531,7 @@ QGCView {
// Mission Item Editor
Item
{
id
:
missionItemEditor
anchors.topMargin
:
_margin
anchors.topMargin
:
planElementSelectorRow
.
visible
?
_margin
:
0
anchors.top
:
planElementSelectorRow
.
visible
?
planElementSelectorRow
.
bottom
:
planElementSelectorRow
.
top
anchors.bottom
:
parent
.
bottom
anchors.right
:
parent
.
right
...
...
@@ -673,10 +673,10 @@ QGCView {
color
:
qgcPal
.
window
title
:
qsTr
(
"
Plan
"
)
z
:
QGroundControl
.
zOrderWidgets
showAlternateIcon
:
[
false
,
false
,
_syncDropDownController
.
dirty
,
false
,
false
,
false
]
rotateImage
:
[
false
,
false
,
_syncDropDownController
.
syncInProgress
,
false
,
false
,
false
]
animateImage
:
[
false
,
false
,
_syncDropDownController
.
dirty
,
false
,
false
,
false
]
buttonEnabled
:
[
true
,
true
,
!
_syncDropDownController
.
syncInProgress
,
true
,
true
,
true
]
showAlternateIcon
:
[
false
,
false
,
false
,
false
,
false
]
rotateImage
:
[
false
,
false
,
false
,
false
,
false
]
animateImage
:
[
false
,
false
,
false
,
false
,
false
]
buttonEnabled
:
[
true
,
true
,
true
,
true
,
true
]
buttonVisible
:
[
true
,
true
,
true
,
true
,
_showZoom
,
_showZoom
]
maxHeight
:
mapScale
.
y
-
toolStrip
.
y
...
...
@@ -684,8 +684,6 @@ QGCView {
property
bool
mySingleComplexItem
:
_singleComplexItem
onMySingleComplexItemChanged
:
console
.
log
(
model
[
1
].
dropPanelComponent
)
model
:
[
{
name
:
"
Waypoint
"
,
...
...
@@ -697,12 +695,6 @@ QGCView {
iconSource
:
"
/qmlimages/MapDrawShape.svg
"
,
dropPanelComponent
:
_singleComplexItem
?
undefined
:
patternDropPanel
},
{
name
:
"
Sync
"
,
iconSource
:
"
/qmlimages/MapSync.svg
"
,
alternateIconSource
:
"
/qmlimages/MapSyncChanged.svg
"
,
dropPanelComponent
:
syncDropPanel
},
{
name
:
"
Center
"
,
iconSource
:
"
/qmlimages/MapCenter.svg
"
,
...
...
@@ -728,16 +720,10 @@ QGCView {
addComplexItem
(
missionController
.
complexMissionItemNames
[
0
])
}
break
case
5
:
case
3
:
editorMap
.
zoomLevel
+=
0.5
break
case
6
:
editorMap
.
zoomLevel
-=
0.5
break
case
5
:
editorMap
.
zoomLevel
+=
0.5
break
case
6
:
case
4
:
editorMap
.
zoomLevel
-=
0.5
break
}
...
...
@@ -834,12 +820,12 @@ QGCView {
columnSpacing
:
ScreenTools
.
defaultFontPixelWidth
QGCButton
{
text
:
qsTr
(
"
S
end To Vehicl
e
"
)
text
:
qsTr
(
"
S
av
e
"
)
Layout.fillWidth
:
true
enabled
:
_activeVehicle
&&
!
_syncDropDownController
.
syncInProgress
enabled
:
!
_syncDropDownController
.
syncInProgress
onClicked
:
{
dropPanel
.
hide
()
_syncDropDownController
.
s
endToVehicl
e
()
_syncDropDownController
.
s
av
e
()
}
}
...
...
src/QmlControls/ParameterEditorDialog.qml
View file @
08ace3c5
...
...
@@ -200,6 +200,7 @@ QGCViewDialog {
wrapMode
:
Text
.
WordWrap
text
:
qsTr
(
"
Warning: Modifying values while vehicle is in flight can lead to vehicle instability and possible vehicle loss.
"
)
+
qsTr
(
"
Make sure you know what you are doing and double-check your values before Save!
"
)
visible
:
fact
.
componentId
!=
-
1
}
QGCCheckBox
{
...
...
src/QmlControls/QFileDialogController.cc
View file @
08ace3c5
...
...
@@ -27,7 +27,7 @@ QStringList QFileDialogController::getFiles(const QString& directoryPath, const
foreach
(
const
QFileInfo
&
fileInfo
,
fileInfoList
)
{
qCDebug
(
QFileDialogControllerLog
)
<<
"getFiles found"
<<
fileInfo
.
baseName
();
files
<<
fileInfo
.
baseName
()
+
QStringLiteral
(
"."
)
+
fileExtension
;
files
<<
fileInfo
.
baseName
();
}
return
files
;
...
...
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