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
d4145cb1
Commit
d4145cb1
authored
Aug 24, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'Stable_V3.2' of
https://github.com/mavlink/qgroundcontrol
into StableMerge
parents
08deff4b
9e426b02
Changes
14
Hide whitespace changes
Inline
Side-by-side
Showing
14 changed files
with
138 additions
and
94 deletions
+138
-94
AndroidManifest.xml
android/AndroidManifest.xml
+1
-1
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+18
-4
CameraSection.FactMetaData.json
src/MissionManager/CameraSection.FactMetaData.json
+1
-1
CameraSection.cc
src/MissionManager/CameraSection.cc
+1
-0
CameraSection.h
src/MissionManager/CameraSection.h
+1
-0
MissionManager.cc
src/MissionManager/MissionManager.cc
+60
-74
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+1
-1
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+3
-5
SpeedSection.cc
src/MissionManager/SpeedSection.cc
+17
-2
SpeedSection.h
src/MissionManager/SpeedSection.h
+8
-2
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+6
-2
SurveyItemEditor.qml
src/PlanView/SurveyItemEditor.qml
+18
-0
AppMessages.qml
src/QmlControls/AppMessages.qml
+3
-0
OfflineMap.qml
src/QtLocationPlugin/QMLControl/OfflineMap.qml
+0
-2
No files found.
android/AndroidManifest.xml
View file @
d4145cb1
<?xml version="1.0"?>
<manifest
package=
"org.mavlink.qgroundcontrol"
xmlns:android=
"http://schemas.android.com/apk/res/android"
android:versionName=
"3.0.0-243-gd759437"
android:versionCode=
"300243"
android:installLocation=
"auto"
>
<application
android:hardwareAccelerated=
"true"
android:name=
"org.qtproject.qt5.android.bindings.QtApplication"
android:label=
"-- %%INSERT_APP_NAME%% --"
android:icon=
"@drawable/icon"
>
<application
android:hardwareAccelerated=
"true"
android:name=
"org.qtproject.qt5.android.bindings.QtApplication"
android:label=
"-- %%INSERT_APP_NAME%% --"
android:icon=
"@drawable/icon"
android:debuggable=
"true"
>
<activity
android:configChanges=
"orientation|uiMode|screenLayout|screenSize|smallestScreenSize|locale|fontScale|keyboard|keyboardHidden|navigation"
android:name=
"org.mavlink.qgroundcontrol.QGCActivity"
android:label=
"-- %%INSERT_APP_NAME%% --"
android:screenOrientation=
"sensorLandscape"
android:launchMode=
"singleTask"
android:keepScreenOn=
"true"
>
<intent-filter>
<action
android:name=
"android.intent.action.MAIN"
/>
...
...
src/FlightDisplay/GuidedActionsController.qml
View file @
d4145cb1
...
...
@@ -122,8 +122,8 @@ Item {
property
bool
_hideOrbit
:
!
QGroundControl
.
corePlugin
.
options
.
guidedBarShowOrbit
property
bool
_vehicleWasFlying
:
false
//Handy code for debugging state problems
/*
//Handy code for debugging state problems
property bool __guidedModeSupported: _activeVehicle ? _activeVehicle.guidedModeSupported : false
property bool __pauseVehicleSupported: _activeVehicle ? _activeVehicle.pauseVehicleSupported : false
property bool __flightMode: _flightMode
...
...
@@ -140,6 +140,23 @@ Item {
on__FlightModeChanged: _outputState()
on__GuidedModeSupportedChanged: _outputState()
on__PauseVehicleSupportedChanged: _outputState()
on_CurrentMissionIndexChanged: console.log("_currentMissionIndex", _currentMissionIndex)
on_ResumeMissionIndexChanged: console.log("_resumeMissionIndex", _resumeMissionIndex)
onShowResumeMissionChanged: {
console.log("showResumeMission", showResumeMission)
_outputState()
}
onShowStartMissionChanged: {
console.log("showStartMission", showStartMission)
_outputState()
}
onShowContinueMissionChanged: {
console.log("showContinueMission", showContinueMission)
_outputState()
}
// End of hack
*/
on_VehicleFlyingChanged
:
{
...
...
@@ -150,11 +167,8 @@ Item {
_vehicleWasFlying
=
true
}
}
property
var
_actionData
on_CurrentMissionIndexChanged
:
console
.
log
(
"
_currentMissionIndex
"
,
_currentMissionIndex
)
on_FlightModeChanged
:
{
_vehiclePaused
=
_flightMode
===
_activeVehicle
.
pauseFlightMode
_vehicleInRTLMode
=
_flightMode
===
_activeVehicle
.
rtlFlightMode
...
...
src/MissionManager/CameraSection.FactMetaData.json
View file @
d4145cb1
...
...
@@ -49,7 +49,7 @@
"name"
:
"CameraMode"
,
"shortDescription"
:
"Specify whether the camera should switch to photo or video mode"
,
"type"
:
"uint32"
,
"enumStrings"
:
"
Take photos,Record v
ideo"
,
"enumStrings"
:
"
Photo,V
ideo"
,
"enumValues"
:
"0,1"
,
"defaultValue"
:
0
}
...
...
src/MissionManager/CameraSection.cc
View file @
d4145cb1
...
...
@@ -67,6 +67,7 @@ CameraSection::CameraSection(Vehicle* vehicle, QObject* parent)
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
this
,
&
CameraSection
::
specifyCameraModeChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_updateSpecifiedGimbalYaw
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_updateSpecifiedGimbalYaw
);
}
...
...
src/MissionManager/CameraSection.h
View file @
d4145cb1
...
...
@@ -63,6 +63,7 @@ public:
void
setSpecifyGimbal
(
bool
specifyGimbal
);
void
setSpecifyCameraMode
(
bool
specifyCameraMode
);
///< Signals specifiedGimbalYawChanged
///< @return The gimbal yaw specified by this item, NaN if not specified
double
specifiedGimbalYaw
(
void
)
const
;
...
...
src/MissionManager/MissionManager.cc
View file @
d4145cb1
...
...
@@ -90,9 +90,24 @@ void MissionManager::generateResumeMission(int resumeIndex)
}
}
resumeIndex
=
qMin
(
resumeIndex
,
_missionItems
.
count
()
-
1
);
// Be anal about crap input
resumeIndex
=
qMax
(
0
,
qMin
(
resumeIndex
,
_missionItems
.
count
()
-
1
));
// Adjust resume index to be a location based command
const
MissionCommandUIInfo
*
uiInfo
=
qgcApp
()
->
toolbox
()
->
missionCommandTree
()
->
getUIInfo
(
_vehicle
,
_missionItems
[
resumeIndex
]
->
command
());
if
(
!
uiInfo
||
uiInfo
->
isStandaloneCoordinate
()
||
!
uiInfo
->
specifiesCoordinate
())
{
// We have to back up to the last command which the vehicle flies through
while
(
--
resumeIndex
>
0
)
{
uiInfo
=
qgcApp
()
->
toolbox
()
->
missionCommandTree
()
->
getUIInfo
(
_vehicle
,
_missionItems
[
resumeIndex
]
->
command
());
if
(
uiInfo
&&
(
uiInfo
->
specifiesCoordinate
()
&&
!
uiInfo
->
isStandaloneCoordinate
()))
{
// Found it
break
;
}
}
}
resumeIndex
=
qMax
(
0
,
resumeIndex
);
int
seqNum
=
0
;
QList
<
MissionItem
*>
resumeMission
;
QList
<
MAV_CMD
>
includedResumeCommands
;
...
...
@@ -110,114 +125,85 @@ void MissionManager::generateResumeMission(int resumeIndex)
<<
MAV_CMD_IMAGE_STOP_CAPTURE
<<
MAV_CMD_VIDEO_START_CAPTURE
<<
MAV_CMD_VIDEO_STOP_CAPTURE
<<
MAV_CMD_DO_CHANGE_SPEED
;
if
(
_vehicle
->
fixedWing
()
&&
_vehicle
->
px4Firmware
())
{
includedResumeCommands
<<
MAV_CMD_NAV_TAKEOFF
;
}
<<
MAV_CMD_DO_CHANGE_SPEED
<<
MAV_CMD_SET_CAMERA_MODE
<<
MAV_CMD_NAV_TAKEOFF
;
bool
addHomePosition
=
_vehicle
->
firmwarePlugin
()
->
sendHomePositionToVehicle
();
int
setCurrentIndex
=
addHomePosition
?
1
:
0
;
int
resume
CommandCount
=
0
;
int
prefix
CommandCount
=
0
;
for
(
int
i
=
0
;
i
<
_missionItems
.
count
();
i
++
)
{
MissionItem
*
oldItem
=
_missionItems
[
i
];
if
((
i
==
0
&&
addHomePosition
)
||
i
>=
resumeIndex
||
includedResumeCommands
.
contains
(
oldItem
->
command
()))
{
if
(
i
<
resumeIndex
)
{
resume
CommandCount
++
;
prefix
CommandCount
++
;
}
MissionItem
*
newItem
=
new
MissionItem
(
*
oldItem
,
this
);
newItem
->
setIsCurrentItem
(
i
==
setCurrentIndex
);
newItem
->
setSequenceNumber
(
seqNum
++
);
newItem
->
setIsCurrentItem
(
false
);
resumeMission
.
append
(
newItem
);
}
}
prefixCommandCount
=
qMax
(
0
,
qMin
(
prefixCommandCount
,
resumeMission
.
count
()));
// Anal prevention against crashes
// De-dup and remove no-ops from the commands which were added to the front of the mission
bool
foundROI
=
false
;
bool
foundCamTrigDist
=
false
;
QList
<
int
>
imageStartCameraIds
;
QList
<
int
>
imageStopCameraIds
;
QList
<
int
>
videoStartCameraIds
;
QList
<
int
>
videoStopCameraIds
;
while
(
resumeIndex
>=
0
)
{
MissionItem
*
resumeItem
=
resumeMission
[
resumeIndex
];
bool
foundCameraSetMode
=
false
;
bool
foundCameraStartStop
=
false
;
prefixCommandCount
--
;
// Change from count to array index
while
(
prefixCommandCount
>=
0
)
{
MissionItem
*
resumeItem
=
resumeMission
[
prefixCommandCount
];
switch
(
resumeItem
->
command
())
{
case
MAV_CMD_SET_CAMERA_MODE
:
// Only keep the last one
if
(
foundCameraSetMode
)
{
resumeMission
.
removeAt
(
prefixCommandCount
);
}
foundCameraSetMode
=
true
;
break
;
case
MAV_CMD_DO_SET_ROI
:
// Only keep the last one
if
(
foundROI
)
{
resumeMission
.
removeAt
(
resumeIndex
);
resumeMission
.
removeAt
(
prefixCommandCount
);
}
foundROI
=
true
;
break
;
case
MAV_CMD_DO_SET_CAM_TRIGG_DIST
:
// Only keep the last one
if
(
foundCamTrigDist
)
{
resumeMission
.
removeAt
(
resumeIndex
);
case
MAV_CMD_IMAGE_STOP_CAPTURE
:
case
MAV_CMD_VIDEO_START_CAPTURE
:
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
// Only keep the first of these commands that are found
if
(
foundCameraStartStop
)
{
resumeMission
.
removeAt
(
prefixCommandCount
);
}
foundCam
TrigDist
=
true
;
foundCam
eraStartStop
=
true
;
break
;
case
MAV_CMD_IMAGE_START_CAPTURE
:
{
// FIXME: Handle single image capture
int
cameraId
=
resumeItem
->
param1
();
if
(
resumeItem
->
param3
()
==
1
)
{
// This is an individual image capture command, remove it
resumeMission
.
removeAt
(
resumeIndex
);
if
(
resumeItem
->
param3
()
!=
0
)
{
// Remove commands which do not trigger by time
resumeMission
.
removeAt
(
prefixCommandCount
);
break
;
}
// If we already found an image stop, then all image start/stop commands are useless
// De-dup repeated image start commands
// Otherwise keep only the last image start
if
(
imageStopCameraIds
.
contains
(
cameraId
)
||
imageStartCameraIds
.
contains
(
cameraId
))
{
resumeMission
.
removeAt
(
resumeIndex
);
}
if
(
!
imageStopCameraIds
.
contains
(
cameraId
))
{
imageStopCameraIds
.
append
(
cameraId
);
}
}
break
;
case
MAV_CMD_IMAGE_STOP_CAPTURE
:
{
int
cameraId
=
resumeItem
->
param1
();
// Image stop only matters to kill all previous image starts
if
(
!
imageStopCameraIds
.
contains
(
cameraId
))
{
imageStopCameraIds
.
append
(
cameraId
);
}
resumeMission
.
removeAt
(
resumeIndex
);
}
break
;
case
MAV_CMD_VIDEO_START_CAPTURE
:
{
int
cameraId
=
resumeItem
->
param1
();
// If we've already found a video stop, then all video start/stop commands are useless
// De-dup repeated video start commands
// Otherwise keep only the last video start
if
(
videoStopCameraIds
.
contains
(
cameraId
)
||
videoStopCameraIds
.
contains
(
cameraId
))
{
resumeMission
.
removeAt
(
resumeIndex
);
}
if
(
!
videoStopCameraIds
.
contains
(
cameraId
))
{
videoStopCameraIds
.
append
(
cameraId
);
}
}
break
;
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
{
int
cameraId
=
resumeItem
->
param1
();
// Video stop only matters to kill all previous video starts
if
(
!
videoStopCameraIds
.
contains
(
cameraId
))
{
videoStopCameraIds
.
append
(
cameraId
);
if
(
foundCameraStartStop
)
{
// Only keep the first of these commands that are found
resumeMission
.
removeAt
(
prefixCommandCount
);
}
resumeMission
.
removeAt
(
resumeIndex
);
}
foundCameraStartStop
=
true
;
break
;
default:
break
;
}
resumeIndex
--
;
prefixCommandCount
--
;
}
// Adjust sequence numbers and current item
int
seqNum
=
0
;
for
(
int
i
=
0
;
i
<
resumeMission
.
count
();
i
++
)
{
resumeMission
[
i
]
->
setSequenceNumber
(
seqNum
++
);
}
int
setCurrentIndex
=
addHomePosition
?
1
:
0
;
resumeMission
[
setCurrentIndex
]
->
setIsCurrentItem
(
true
);
// Send to vehicle
_clearAndDeleteWriteMissionItems
();
for
(
int
i
=
0
;
i
<
resumeMission
.
count
();
i
++
)
{
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
d4145cb1
...
...
@@ -63,8 +63,8 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
connect
(
&
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
specifiedFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
specifiedFlightSpeedChanged
);
}
int
MissionSettingsItem
::
lastSequenceNumber
(
void
)
const
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
d4145cb1
...
...
@@ -755,13 +755,11 @@ void SimpleMissionItem::_updateOptionalSections(void)
connect
(
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_speedSection
,
&
SpeedSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_speedSection
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SimpleMissionItem
::
specifiedFlightSpeedChanged
);
connect
(
_speedSection
->
flightSpeed
(),
&
Fact
::
rawValueChanged
,
this
,
&
SimpleMissionItem
::
specifiedFlightSpeedChanged
);
connect
(
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_speedSection
,
&
SpeedSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_speedSection
,
&
SpeedSection
::
specifiedFlightSpeedChanged
,
this
,
&
SimpleMissionItem
::
specifiedFlightSpeedChanged
);
emit
cameraSectionChanged
(
_cameraSection
);
emit
speedSectionChanged
(
_speedSection
);
...
...
src/MissionManager/SpeedSection.cc
View file @
d4145cb1
...
...
@@ -38,8 +38,11 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
_flightSpeedFact
.
setMetaData
(
_metaDataMap
[
_flightSpeedName
]);
_flightSpeedFact
.
setRawValue
(
flightSpeed
);
connect
(
this
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SpeedSection
::
settingsSpecifiedChanged
);
connect
(
&
_flightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
SpeedSection
::
_setDirty
);
connect
(
this
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SpeedSection
::
settingsSpecifiedChanged
);
connect
(
&
_flightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
SpeedSection
::
_setDirty
);
connect
(
this
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SpeedSection
::
_updateSpecifiedFlightSpeed
);
connect
(
&
_flightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
SpeedSection
::
_updateSpecifiedFlightSpeed
);
}
bool
SpeedSection
::
settingsSpecified
(
void
)
const
...
...
@@ -134,3 +137,15 @@ bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex
return
false
;
}
double
SpeedSection
::
specifiedFlightSpeed
(
void
)
const
{
return
_specifyFlightSpeed
?
_flightSpeedFact
.
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
SpeedSection
::
_updateSpecifiedFlightSpeed
(
void
)
{
emit
specifiedFlightSpeedChanged
(
specifiedFlightSpeed
());
}
src/MissionManager/SpeedSection.h
View file @
d4145cb1
...
...
@@ -27,6 +27,10 @@ public:
Fact
*
flightSpeed
(
void
)
{
return
&
_flightSpeedFact
;
}
void
setSpecifyFlightSpeed
(
bool
specifyFlightSpeed
);
///< Signals specifiedFlightSpeedChanged
///< @return The flight speed specified by this item, NaN if not specified
double
specifiedFlightSpeed
(
void
)
const
;
// Overrides from Section
bool
available
(
void
)
const
override
{
return
_available
;
}
bool
dirty
(
void
)
const
override
{
return
_dirty
;
}
...
...
@@ -38,10 +42,12 @@ public:
bool
settingsSpecified
(
void
)
const
override
;
signals:
void
specifyFlightSpeedChanged
(
bool
specifyFlightSpeed
);
void
specifyFlightSpeedChanged
(
bool
specifyFlightSpeed
);
void
specifiedFlightSpeedChanged
(
double
flightSpeed
);
private
slots
:
void
_setDirty
(
void
);
void
_setDirty
(
void
);
void
_updateSpecifiedFlightSpeed
(
void
);
private:
bool
_available
;
...
...
src/MissionManager/SurveyMissionItem.cc
View file @
d4145cb1
...
...
@@ -747,7 +747,9 @@ void SurveyMissionItem::_generateGrid(void)
_setSurveyDistance
(
surveyDistance
);
if
(
cameraShots
==
0
&&
_triggerCamera
())
{
cameraShots
=
(
int
)
ceil
(
surveyDistance
/
_triggerDistance
());
cameraShots
=
(
int
)
floor
(
surveyDistance
/
_triggerDistance
());
// Take into account immediate camera trigger at waypoint entry
cameraShots
++
;
}
_setCameraShots
(
cameraShots
);
...
...
@@ -1065,7 +1067,9 @@ int SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLis
// Calc camera shots here if there are no images in turnaround
if
(
_triggerCamera
()
&&
!
_imagesEverywhere
())
{
for
(
int
i
=
0
;
i
<
resultLines
.
count
();
i
++
)
{
cameraShots
+=
(
int
)
ceil
(
resultLines
[
i
].
length
()
/
_triggerDistance
());
cameraShots
+=
(
int
)
floor
(
resultLines
[
i
].
length
()
/
_triggerDistance
());
// Take into account immediate camera trigger at waypoint entry
cameraShots
++
;
}
}
...
...
src/PlanView/SurveyItemEditor.qml
View file @
d4145cb1
...
...
@@ -590,6 +590,24 @@ Rectangle {
Layout.fillWidth
:
true
}
FactCheckBox
{
text
:
qsTr
(
"
Hover and capture image
"
)
fact
:
missionItem
.
hoverAndCapture
visible
:
missionItem
.
hoverAndCaptureAllowed
Layout.columnSpan
:
2
onClicked
:
{
if
(
checked
)
{
missionItem
.
cameraTriggerInTurnaround
.
rawValue
=
false
}
}
}
FactCheckBox
{
text
:
qsTr
(
"
Take images in turnarounds
"
)
fact
:
missionItem
.
cameraTriggerInTurnaround
enabled
:
!
missionItem
.
hoverAndCapture
.
rawValue
Layout.columnSpan
:
2
}
QGCCheckBox
{
text
:
qsTr
(
"
Refly at 90 degree offset
"
)
...
...
src/QmlControls/AppMessages.qml
View file @
d4145cb1
...
...
@@ -24,6 +24,8 @@ QGCView {
property
bool
loaded
:
false
property
var
_qgcView
:
qgcView
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
panel
.
enabled
}
Component
{
...
...
@@ -117,6 +119,7 @@ QGCView {
nameFilters
:
[
qsTr
(
"
Log files (*.txt)
"
),
qsTr
(
"
All Files (*)
"
)]
selectExisting
:
false
title
:
qsTr
(
"
Select log save file
"
)
qgcView
:
_qgcView
onAcceptedForSave
:
{
debugMessageModel
.
writeMessages
(
file
);
visible
=
false
;
...
...
src/QtLocationPlugin/QMLControl/OfflineMap.qml
View file @
d4145cb1
...
...
@@ -342,8 +342,6 @@ QGCView {
property
bool
isSatelliteMap
:
activeMapType
.
name
.
indexOf
(
"
Satellite
"
)
>
-
1
||
activeMapType
.
name
.
indexOf
(
"
Hybrid
"
)
>
-
1
plugin
:
Plugin
{
name
:
"
QGroundControl
"
}
MapRectangle
{
id
:
mapBoundary
border.width
:
2
...
...
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