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
da2fdf65
Commit
da2fdf65
authored
Feb 27, 2019
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
5fb168e1
Changes
12
Show whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
383 additions
and
71 deletions
+383
-71
qgroundcontrol.pro
qgroundcontrol.pro
+2
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+25
-13
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+9
-0
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+4
-0
APMMavlinkStreamRate.SettingsGroup.json
src/Settings/APMMavlinkStreamRate.SettingsGroup.json
+64
-0
APMMavlinkStreamRateSettings.cc
src/Settings/APMMavlinkStreamRateSettings.cc
+83
-0
APMMavlinkStreamRateSettings.h
src/Settings/APMMavlinkStreamRateSettings.h
+42
-0
App.SettingsGroup.json
src/Settings/App.SettingsGroup.json
+5
-4
SettingsManager.cc
src/Settings/SettingsManager.cc
+21
-19
SettingsManager.h
src/Settings/SettingsManager.h
+32
-28
MavlinkSettings.qml
src/ui/preferences/MavlinkSettings.qml
+95
-7
No files found.
qgroundcontrol.pro
View file @
da2fdf65
...
...
@@ -596,6 +596,7 @@ HEADERS += \
src
/
QmlControls
/
RCChannelMonitorController
.
h
\
src
/
QmlControls
/
ScreenToolsController
.
h
\
src
/
QtLocationPlugin
/
QMLControl
/
QGCMapEngineManager
.
h
\
src
/
Settings
/
APMMavlinkStreamRateSettings
.
h
\
src
/
Settings
/
AppSettings
.
h
\
src
/
Settings
/
AutoConnectSettings
.
h
\
src
/
Settings
/
BrandImageSettings
.
h
\
...
...
@@ -799,6 +800,7 @@ SOURCES += \
src
/
QmlControls
/
RCChannelMonitorController
.
cc
\
src
/
QmlControls
/
ScreenToolsController
.
cc
\
src
/
QtLocationPlugin
/
QMLControl
/
QGCMapEngineManager
.
cc
\
src
/
Settings
/
APMMavlinkStreamRateSettings
.
cc
\
src
/
Settings
/
AppSettings
.
cc
\
src
/
Settings
/
AutoConnectSettings
.
cc
\
src
/
Settings
/
BrandImageSettings
.
cc
\
...
...
qgroundcontrol.qrc
View file @
da2fdf65
...
...
@@ -210,6 +210,7 @@
<file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file>
</qresource>
<qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
<file alias="CameraCalc.FactMetaData.json">src/MissionManager/CameraCalc.FactMetaData.json</file>
<file alias="CameraSpec.FactMetaData.json">src/MissionManager/CameraSpec.FactMetaData.json</file>
<file alias="CorridorScan.SettingsGroup.json">src/MissionManager/CorridorScan.SettingsGroup.json</file>
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
da2fdf65
...
...
@@ -19,6 +19,7 @@
#include "QGCFileDownload.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "APMMavlinkStreamRateSettings.h"
#include <QTcpSocket>
...
...
@@ -614,13 +615,30 @@ void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* mes
void
APMFirmwarePlugin
::
initializeStreamRates
(
Vehicle
*
vehicle
)
{
vehicle
->
requestDataStream
(
MAV_DATA_STREAM_RAW_SENSORS
,
2
);
vehicle
->
requestDataStream
(
MAV_DATA_STREAM_EXTENDED_STATUS
,
2
);
vehicle
->
requestDataStream
(
MAV_DATA_STREAM_RC_CHANNELS
,
2
);
vehicle
->
requestDataStream
(
MAV_DATA_STREAM_POSITION
,
3
);
vehicle
->
requestDataStream
(
MAV_DATA_STREAM_EXTRA1
,
10
);
vehicle
->
requestDataStream
(
MAV_DATA_STREAM_EXTRA2
,
10
);
vehicle
->
requestDataStream
(
MAV_DATA_STREAM_EXTRA3
,
3
);
APMMavlinkStreamRateSettings
*
streamRates
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
apmMavlinkStreamRateSettings
();
struct
StreamInfo_s
{
MAV_DATA_STREAM
mavStream
;
int
streamRate
;
};
StreamInfo_s
rgStreamInfo
[]
=
{
{
MAV_DATA_STREAM_RAW_SENSORS
,
streamRates
->
streamRateRawSensors
()
->
rawValue
().
toInt
()
},
{
MAV_DATA_STREAM_EXTENDED_STATUS
,
streamRates
->
streamRateExtendedStatus
()
->
rawValue
().
toInt
()
},
{
MAV_DATA_STREAM_RC_CHANNELS
,
streamRates
->
streamRateRCChannels
()
->
rawValue
().
toInt
()
},
{
MAV_DATA_STREAM_POSITION
,
streamRates
->
streamRatePosition
()
->
rawValue
().
toInt
()
},
{
MAV_DATA_STREAM_EXTRA1
,
streamRates
->
streamRateExtra1
()
->
rawValue
().
toInt
()
},
{
MAV_DATA_STREAM_EXTRA2
,
streamRates
->
streamRateExtra2
()
->
rawValue
().
toInt
()
},
{
MAV_DATA_STREAM_EXTRA3
,
streamRates
->
streamRateExtra3
()
->
rawValue
().
toInt
()
},
};
for
(
size_t
i
=
0
;
i
<
sizeof
(
rgStreamInfo
)
/
sizeof
(
rgStreamInfo
[
0
]);
i
++
)
{
const
StreamInfo_s
&
streamInfo
=
rgStreamInfo
[
i
];
if
(
streamInfo
.
streamRate
>=
0
)
{
vehicle
->
requestDataStream
(
streamInfo
.
mavStream
,
static_cast
<
uint16_t
>
(
streamInfo
.
streamRate
));
}
}
}
...
...
@@ -733,22 +751,16 @@ QString APMFirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
switch
(
vehicleType
)
{
case
MAV_TYPE_GENERIC
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoCommon.json"
);
break
;
case
MAV_TYPE_FIXED_WING
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoFixedWing.json"
);
break
;
case
MAV_TYPE_QUADROTOR
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoMultiRotor.json"
);
break
;
case
MAV_TYPE_VTOL_QUADROTOR
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoVTOL.json"
);
break
;
case
MAV_TYPE_SUBMARINE
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoSub.json"
);
break
;
case
MAV_TYPE_GROUND_ROVER
:
return
QStringLiteral
(
":/json/APM/MavCmdInfoRover.json"
);
break
;
default:
qWarning
()
<<
"APMFirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:"
<<
vehicleType
;
return
QString
();
...
...
src/QmlControls/QGroundControlQmlGlobal.cc
View file @
da2fdf65
...
...
@@ -178,6 +178,15 @@ int QGroundControlQmlGlobal::supportedFirmwareCount()
return
_firmwarePluginManager
->
supportedFirmwareTypes
().
count
();
}
bool
QGroundControlQmlGlobal
::
px4ProFirmwareSupported
()
{
return
_firmwarePluginManager
->
supportedFirmwareTypes
().
contains
(
MAV_AUTOPILOT_PX4
);
}
bool
QGroundControlQmlGlobal
::
apmFirmwareSupported
()
{
return
_firmwarePluginManager
->
supportedFirmwareTypes
().
contains
(
MAV_AUTOPILOT_ARDUPILOTMEGA
);
}
bool
QGroundControlQmlGlobal
::
linesIntersect
(
QPointF
line1A
,
QPointF
line1B
,
QPointF
line2A
,
QPointF
line2B
)
{
...
...
src/QmlControls/QGroundControlQmlGlobal.h
View file @
da2fdf65
...
...
@@ -70,6 +70,8 @@ public:
Q_PROPERTY
(
bool
taisyncSupported
READ
taisyncSupported
CONSTANT
)
Q_PROPERTY
(
int
supportedFirmwareCount
READ
supportedFirmwareCount
CONSTANT
)
Q_PROPERTY
(
bool
px4ProFirmwareSupported
READ
px4ProFirmwareSupported
CONSTANT
)
Q_PROPERTY
(
int
apmFirmwareSupported
READ
apmFirmwareSupported
CONSTANT
)
Q_PROPERTY
(
qreal
zOrderTopMost
READ
zOrderTopMost
CONSTANT
)
///< z order for top most items, toolbar, main window sub view
Q_PROPERTY
(
qreal
zOrderWidgets
READ
zOrderWidgets
CONSTANT
)
///< z order value to widgets, for example: zoom controls, hud widgetss
...
...
@@ -180,6 +182,8 @@ public:
int
mavlinkSystemID
()
{
return
_toolbox
->
mavlinkProtocol
()
->
getSystemId
();
}
int
supportedFirmwareCount
();
bool
px4ProFirmwareSupported
();
bool
apmFirmwareSupported
();
bool
skipSetupPage
()
{
return
_skipSetupPage
;
}
void
setSkipSetupPage
(
bool
skip
);
...
...
src/Settings/APMMavlinkStreamRate.SettingsGroup.json
0 → 100644
View file @
da2fdf65
{
"QGC.MetaData.Defines"
:
{
"StreamRateEnumStrings"
:
"Controlled By Vehicle,0 hz,1 hz,2 hz,3 hz,4 hz,5 hz,6 hz,7 hz,8 hz,9 hz,10 hz,50 hz,100 hz"
,
"StreamRateEnumValues"
:
"-1,0,1,2,3,4,5,6,7,8,9,10,50,100"
},
"QGC.MetaData.Facts"
:
[
{
"name"
:
"streamRateRawSensors"
,
"shortDescription"
:
"Stream rate for MAVLink Raw Sensors telemetry stream."
,
"type"
:
"int32"
,
"enumStrings"
:
"QGC.MetaData.Defines.StreamRateEnumStrings"
,
"enumValues"
:
"QGC.MetaData.Defines.StreamRateEnumValues"
,
"defaultValue"
:
2
},
{
"name"
:
"streamRateExtendedStatus"
,
"shortDescription"
:
"Stream rate for MAVLink Extended Status telemetry stream."
,
"type"
:
"int32"
,
"enumStrings"
:
"QGC.MetaData.Defines.StreamRateEnumStrings"
,
"enumValues"
:
"QGC.MetaData.Defines.StreamRateEnumValues"
,
"defaultValue"
:
2
},
{
"name"
:
"streamRateRCChannels"
,
"shortDescription"
:
"Stream rate for MAVLink RC Channels telemetry stream."
,
"type"
:
"int32"
,
"enumStrings"
:
"QGC.MetaData.Defines.StreamRateEnumStrings"
,
"enumValues"
:
"QGC.MetaData.Defines.StreamRateEnumValues"
,
"defaultValue"
:
2
},
{
"name"
:
"streamRatePosition"
,
"shortDescription"
:
"Stream rate for MAVLink Position telemetry stream."
,
"type"
:
"int32"
,
"enumStrings"
:
"QGC.MetaData.Defines.StreamRateEnumStrings"
,
"enumValues"
:
"QGC.MetaData.Defines.StreamRateEnumValues"
,
"defaultValue"
:
3
},
{
"name"
:
"streamRateExtra1"
,
"shortDescription"
:
"Stream rate for MAVLink Extra1 telemetry stream."
,
"type"
:
"int32"
,
"enumStrings"
:
"QGC.MetaData.Defines.StreamRateEnumStrings"
,
"enumValues"
:
"QGC.MetaData.Defines.StreamRateEnumValues"
,
"defaultValue"
:
10
},
{
"name"
:
"streamRateExtra2"
,
"shortDescription"
:
"Stream rate for MAVLink Extra2 telemetry stream."
,
"type"
:
"int32"
,
"enumStrings"
:
"QGC.MetaData.Defines.StreamRateEnumStrings"
,
"enumValues"
:
"QGC.MetaData.Defines.StreamRateEnumValues"
,
"defaultValue"
:
10
},
{
"name"
:
"streamRateExtra3"
,
"shortDescription"
:
"Stream rate for MAVLink Extra3 telemetry stream."
,
"type"
:
"int32"
,
"enumStrings"
:
"QGC.MetaData.Defines.StreamRateEnumStrings"
,
"enumValues"
:
"QGC.MetaData.Defines.StreamRateEnumValues"
,
"defaultValue"
:
3
}
]
}
src/Settings/APMMavlinkStreamRateSettings.cc
0 → 100644
View file @
da2fdf65
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "APMMavlinkStreamRateSettings.h"
#include "QGCApplication.h"
#include <QQmlEngine>
#include <QtQml>
DECLARE_SETTINGGROUP
(
APMMavlinkStreamRate
,
"APMMavlinkStreamRate"
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
qmlRegisterUncreatableType
<
APMMavlinkStreamRateSettings
>
(
"QGroundControl.SettingsManager"
,
1
,
0
,
"APMMavlinkStreamRateSettings"
,
"Reference only"
);
connect
(
streamRateRawSensors
(),
&
Fact
::
rawValueChanged
,
this
,
&
APMMavlinkStreamRateSettings
::
_updateStreamRateRawSensors
);
connect
(
streamRateExtendedStatus
(),
&
Fact
::
rawValueChanged
,
this
,
&
APMMavlinkStreamRateSettings
::
_updateStreamRateExtendedStatus
);
connect
(
streamRateRCChannels
(),
&
Fact
::
rawValueChanged
,
this
,
&
APMMavlinkStreamRateSettings
::
_updateStreamRateRCChannels
);
connect
(
streamRatePosition
(),
&
Fact
::
rawValueChanged
,
this
,
&
APMMavlinkStreamRateSettings
::
_updateStreamRatePosition
);
connect
(
streamRateExtra1
(),
&
Fact
::
rawValueChanged
,
this
,
&
APMMavlinkStreamRateSettings
::
_updateStreamRateExtra1
);
connect
(
streamRateExtra2
(),
&
Fact
::
rawValueChanged
,
this
,
&
APMMavlinkStreamRateSettings
::
_updateStreamRateExtra2
);
connect
(
streamRateExtra3
(),
&
Fact
::
rawValueChanged
,
this
,
&
APMMavlinkStreamRateSettings
::
_updateStreamRateExtra3
);
}
DECLARE_SETTINGSFACT
(
APMMavlinkStreamRateSettings
,
streamRateRawSensors
)
DECLARE_SETTINGSFACT
(
APMMavlinkStreamRateSettings
,
streamRateExtendedStatus
)
DECLARE_SETTINGSFACT
(
APMMavlinkStreamRateSettings
,
streamRateRCChannels
)
DECLARE_SETTINGSFACT
(
APMMavlinkStreamRateSettings
,
streamRatePosition
)
DECLARE_SETTINGSFACT
(
APMMavlinkStreamRateSettings
,
streamRateExtra1
)
DECLARE_SETTINGSFACT
(
APMMavlinkStreamRateSettings
,
streamRateExtra2
)
DECLARE_SETTINGSFACT
(
APMMavlinkStreamRateSettings
,
streamRateExtra3
)
void
APMMavlinkStreamRateSettings
::
_updateStreamRateWorker
(
MAV_DATA_STREAM
mavStream
,
QVariant
rateVar
)
{
Vehicle
*
activeVehicle
=
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
();
if
(
activeVehicle
)
{
int
streamRate
=
rateVar
.
toInt
();
if
(
streamRate
>=
0
)
{
activeVehicle
->
requestDataStream
(
mavStream
,
static_cast
<
uint16_t
>
(
streamRate
));
}
}
}
void
APMMavlinkStreamRateSettings
::
_updateStreamRateRawSensors
(
QVariant
value
)
{
_updateStreamRateWorker
(
MAV_DATA_STREAM_RAW_SENSORS
,
value
);
}
void
APMMavlinkStreamRateSettings
::
_updateStreamRateExtendedStatus
(
QVariant
value
)
{
_updateStreamRateWorker
(
MAV_DATA_STREAM_EXTENDED_STATUS
,
value
);
}
void
APMMavlinkStreamRateSettings
::
_updateStreamRateRCChannels
(
QVariant
value
)
{
_updateStreamRateWorker
(
MAV_DATA_STREAM_RC_CHANNELS
,
value
);
}
void
APMMavlinkStreamRateSettings
::
_updateStreamRatePosition
(
QVariant
value
)
{
_updateStreamRateWorker
(
MAV_DATA_STREAM_POSITION
,
value
);
}
void
APMMavlinkStreamRateSettings
::
_updateStreamRateExtra1
(
QVariant
value
)
{
_updateStreamRateWorker
(
MAV_DATA_STREAM_EXTRA1
,
value
);
}
void
APMMavlinkStreamRateSettings
::
_updateStreamRateExtra2
(
QVariant
value
)
{
_updateStreamRateWorker
(
MAV_DATA_STREAM_EXTRA2
,
value
);
}
void
APMMavlinkStreamRateSettings
::
_updateStreamRateExtra3
(
QVariant
value
)
{
_updateStreamRateWorker
(
MAV_DATA_STREAM_EXTRA3
,
value
);
}
src/Settings/APMMavlinkStreamRateSettings.h
0 → 100644
View file @
da2fdf65
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "SettingsGroup.h"
#include "QGCMAVLink.h"
class
APMMavlinkStreamRateSettings
:
public
SettingsGroup
{
Q_OBJECT
public:
APMMavlinkStreamRateSettings
(
QObject
*
parent
=
nullptr
);
DEFINE_SETTING_NAME_GROUP
()
DEFINE_SETTINGFACT
(
streamRateRawSensors
)
DEFINE_SETTINGFACT
(
streamRateExtendedStatus
)
DEFINE_SETTINGFACT
(
streamRateRCChannels
)
DEFINE_SETTINGFACT
(
streamRatePosition
)
DEFINE_SETTINGFACT
(
streamRateExtra1
)
DEFINE_SETTINGFACT
(
streamRateExtra2
)
DEFINE_SETTINGFACT
(
streamRateExtra3
)
private
slots
:
void
_updateStreamRateRawSensors
(
QVariant
value
);
void
_updateStreamRateExtendedStatus
(
QVariant
value
);
void
_updateStreamRateRCChannels
(
QVariant
value
);
void
_updateStreamRatePosition
(
QVariant
value
);
void
_updateStreamRateExtra1
(
QVariant
value
);
void
_updateStreamRateExtra2
(
QVariant
value
);
void
_updateStreamRateExtra3
(
QVariant
value
);
private:
void
_updateStreamRateWorker
(
MAV_DATA_STREAM
mavStream
,
QVariant
rateVar
);
};
src/Settings/App.SettingsGroup.json
View file @
da2fdf65
...
...
@@ -204,7 +204,8 @@
"name"
:
"apmStartMavlinkStreams"
,
"shortDescription"
:
"Request start of MAVLink telemetry streams (ArduPilot only)"
,
"type"
:
"bool"
,
"defaultValue"
:
true
"defaultValue"
:
true
,
"qgcRebootRequired"
:
true
},
{
"name"
:
"enableTaisync"
,
...
...
src/Settings/SettingsManager.cc
View file @
da2fdf65
...
...
@@ -26,6 +26,7 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
,
_flyViewSettings
(
nullptr
)
,
_planViewSettings
(
nullptr
)
,
_brandImageSettings
(
nullptr
)
,
_apmMavlinkStreamRateSettings
(
nullptr
)
{
}
...
...
@@ -45,6 +46,7 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
_flyViewSettings
=
new
FlyViewSettings
(
this
);
_planViewSettings
=
new
PlanViewSettings
(
this
);
_brandImageSettings
=
new
BrandImageSettings
(
this
);
_apmMavlinkStreamRateSettings
=
new
APMMavlinkStreamRateSettings
(
this
);
#if defined(QGC_AIRMAP_ENABLED)
_airMapSettings
=
new
AirMapSettings
(
this
);
#endif
...
...
src/Settings/SettingsManager.h
View file @
da2fdf65
...
...
@@ -23,6 +23,7 @@
#include "FlyViewSettings.h"
#include "PlanViewSettings.h"
#include "BrandImageSettings.h"
#include "APMMavlinkStreamRateSettings.h"
#if defined(QGC_AIRMAP_ENABLED)
#include "AirMapSettings.h"
#endif
...
...
@@ -48,6 +49,7 @@ public:
Q_PROPERTY
(
QObject
*
flyViewSettings
READ
flyViewSettings
CONSTANT
)
Q_PROPERTY
(
QObject
*
planViewSettings
READ
planViewSettings
CONSTANT
)
Q_PROPERTY
(
QObject
*
brandImageSettings
READ
brandImageSettings
CONSTANT
)
Q_PROPERTY
(
QObject
*
apmMavlinkStreamRateSettings
READ
apmMavlinkStreamRateSettings
CONSTANT
)
// Override from QGCTool
virtual
void
setToolbox
(
QGCToolbox
*
toolbox
);
...
...
@@ -64,6 +66,7 @@ public:
FlyViewSettings
*
flyViewSettings
(
void
)
{
return
_flyViewSettings
;
}
PlanViewSettings
*
planViewSettings
(
void
)
{
return
_planViewSettings
;
}
BrandImageSettings
*
brandImageSettings
(
void
)
{
return
_brandImageSettings
;
}
APMMavlinkStreamRateSettings
*
apmMavlinkStreamRateSettings
(
void
)
{
return
_apmMavlinkStreamRateSettings
;
}
private:
#if defined(QGC_AIRMAP_ENABLED)
...
...
@@ -78,6 +81,7 @@ private:
FlyViewSettings
*
_flyViewSettings
;
PlanViewSettings
*
_planViewSettings
;
BrandImageSettings
*
_brandImageSettings
;
APMMavlinkStreamRateSettings
*
_apmMavlinkStreamRateSettings
;
};
#endif
src/ui/preferences/MavlinkSettings.qml
View file @
da2fdf65
...
...
@@ -12,6 +12,7 @@ import QtQuick 2.3
import
QtQuick
.
Controls
1.2
import
QtQuick
.
Controls
.
Styles
1.4
import
QtQuick
.
Dialogs
1.2
import
QtQuick
.
Layouts
1.2
import
QGroundControl
1.0
import
QGroundControl
.
FactSystem
1.0
...
...
@@ -33,6 +34,7 @@ Rectangle {
property
bool
_uploadedSelected
:
false
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
var
_showMavlinkLog
:
QGroundControl
.
corePlugin
.
options
.
showMavlinkLogOptions
property
bool
_showAPMStreamRates
:
QGroundControl
.
apmFirmwareSupported
&&
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
visible
QGCPalette
{
id
:
qgcPal
}
...
...
@@ -143,11 +145,6 @@ Rectangle {
}
}
FactCheckBox
{
text
:
fact
.
shortDescription
fact
:
QGroundControl
.
settingsManager
.
appSettings
.
apmStartMavlinkStreams
}
QGCCheckBox
{
text
:
qsTr
(
"
Only accept MAVs with same protocol version
"
)
checked
:
QGroundControl
.
isVersionCheckEnabled
...
...
@@ -158,6 +155,97 @@ Rectangle {
}
}
//-----------------------------------------------------------------
//-- Stream Rates
Item
{
id
:
apmStreamRatesLabel
width
:
__mavlinkRoot
.
width
*
0.8
height
:
streamRatesLabel
.
height
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
_showAPMStreamRates
QGCLabel
{
id
:
streamRatesLabel
text
:
qsTr
(
"
Telemetry Stream Rates (ArduPilot Only)
"
)
font.family
:
ScreenTools
.
demiboldFontFamily
}
}
Rectangle
{
height
:
streamRatesColumn
.
height
+
(
ScreenTools
.
defaultFontPixelHeight
*
2
)
width
:
__mavlinkRoot
.
width
*
0.8
color
:
qgcPal
.
windowShade
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
_showAPMStreamRates
ColumnLayout
{
id
:
streamRatesColumn
spacing
:
ScreenTools
.
defaultFontPixelHeight
/
2
anchors.centerIn
:
parent
property
bool
allStreamsControlledByVehicle
:
!
QGroundControl
.
settingsManager
.
appSettings
.
apmStartMavlinkStreams
.
rawValue
QGCCheckBox
{
text
:
qsTr
(
"
All Streams Controlled By Vehicle Settings
"
)
checked
:
streamRatesColumn
.
allStreamsControlledByVehicle
onClicked
:
QGroundControl
.
settingsManager
.
appSettings
.
apmStartMavlinkStreams
.
rawValue
=
!
checked
}
GridLayout
{
columns
:
2
enabled
:
!
streamRatesColumn
.
allStreamsControlledByVehicle
QGCLabel
{
text
:
qsTr
(
"
Raw Sensors
"
)
}
FactComboBox
{
fact
:
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
streamRateRawSensors
indexModel
:
false
Layout.preferredWidth
:
_valueWidth
}
QGCLabel
{
text
:
qsTr
(
"
Extended Status
"
)
}
FactComboBox
{
fact
:
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
streamRateExtendedStatus
indexModel
:
false
Layout.preferredWidth
:
_valueWidth
}
QGCLabel
{
text
:
qsTr
(
"
RC Channel
"
)
}
FactComboBox
{
fact
:
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
streamRateRCChannels
indexModel
:
false
Layout.preferredWidth
:
_valueWidth
}
QGCLabel
{
text
:
qsTr
(
"
Position
"
)
}
FactComboBox
{
fact
:
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
streamRatePosition
indexModel
:
false
Layout.preferredWidth
:
_valueWidth
}
QGCLabel
{
text
:
qsTr
(
"
Extra 1
"
)
}
FactComboBox
{
fact
:
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
streamRateExtra1
indexModel
:
false
Layout.preferredWidth
:
_valueWidth
}
QGCLabel
{
text
:
qsTr
(
"
Extra 2
"
)
}
FactComboBox
{
fact
:
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
streamRateExtra2
indexModel
:
false
Layout.preferredWidth
:
_valueWidth
}
QGCLabel
{
text
:
qsTr
(
"
Extra 3
"
)
}
FactComboBox
{
fact
:
QGroundControl
.
settingsManager
.
apmMavlinkStreamRateSettings
.
streamRateExtra3
indexModel
:
false
Layout.preferredWidth
:
_valueWidth
}
}
}
}
//-----------------------------------------------------------------
//-- Mavlink Status
Item
{
width
:
__mavlinkRoot
.
width
*
0.8
...
...
@@ -253,7 +341,7 @@ Rectangle {
visible
:
_showMavlinkLog
QGCLabel
{
id
:
mavlogLabel
text
:
qsTr
(
"
MAVLink 2.0 Logging (PX4
Firmware
Only)
"
)
text
:
qsTr
(
"
MAVLink 2.0 Logging (PX4
Pro
Only)
"
)
font.family
:
ScreenTools
.
demiboldFontFamily
}
}
...
...
@@ -315,7 +403,7 @@ Rectangle {
visible
:
_showMavlinkLog
QGCLabel
{
id
:
logLabel
text
:
qsTr
(
"
MAVLink 2.0 Log Uploads (PX4
Firmware
Only)
"
)
text
:
qsTr
(
"
MAVLink 2.0 Log Uploads (PX4
Pro
Only)
"
)
font.family
:
ScreenTools
.
demiboldFontFamily
}
}
...
...
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