Commit da2fdf65 authored by Don Gagne's avatar Don Gagne

parent 5fb168e1
...@@ -596,6 +596,7 @@ HEADERS += \ ...@@ -596,6 +596,7 @@ HEADERS += \
src/QmlControls/RCChannelMonitorController.h \ src/QmlControls/RCChannelMonitorController.h \
src/QmlControls/ScreenToolsController.h \ src/QmlControls/ScreenToolsController.h \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \ src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \
src/Settings/APMMavlinkStreamRateSettings.h \
src/Settings/AppSettings.h \ src/Settings/AppSettings.h \
src/Settings/AutoConnectSettings.h \ src/Settings/AutoConnectSettings.h \
src/Settings/BrandImageSettings.h \ src/Settings/BrandImageSettings.h \
...@@ -799,6 +800,7 @@ SOURCES += \ ...@@ -799,6 +800,7 @@ SOURCES += \
src/QmlControls/RCChannelMonitorController.cc \ src/QmlControls/RCChannelMonitorController.cc \
src/QmlControls/ScreenToolsController.cc \ src/QmlControls/ScreenToolsController.cc \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \ src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \
src/Settings/APMMavlinkStreamRateSettings.cc \
src/Settings/AppSettings.cc \ src/Settings/AppSettings.cc \
src/Settings/AutoConnectSettings.cc \ src/Settings/AutoConnectSettings.cc \
src/Settings/BrandImageSettings.cc \ src/Settings/BrandImageSettings.cc \
......
...@@ -210,6 +210,7 @@ ...@@ -210,6 +210,7 @@
<file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file> <file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file>
</qresource> </qresource>
<qresource prefix="/json"> <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="CameraCalc.FactMetaData.json">src/MissionManager/CameraCalc.FactMetaData.json</file>
<file alias="CameraSpec.FactMetaData.json">src/MissionManager/CameraSpec.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> <file alias="CorridorScan.SettingsGroup.json">src/MissionManager/CorridorScan.SettingsGroup.json</file>
......
...@@ -19,6 +19,7 @@ ...@@ -19,6 +19,7 @@
#include "QGCFileDownload.h" #include "QGCFileDownload.h"
#include "SettingsManager.h" #include "SettingsManager.h"
#include "AppSettings.h" #include "AppSettings.h"
#include "APMMavlinkStreamRateSettings.h"
#include <QTcpSocket> #include <QTcpSocket>
...@@ -614,13 +615,30 @@ void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* mes ...@@ -614,13 +615,30 @@ void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* mes
void APMFirmwarePlugin::initializeStreamRates(Vehicle* vehicle) void APMFirmwarePlugin::initializeStreamRates(Vehicle* vehicle)
{ {
vehicle->requestDataStream(MAV_DATA_STREAM_RAW_SENSORS, 2); APMMavlinkStreamRateSettings* streamRates = qgcApp()->toolbox()->settingsManager()->apmMavlinkStreamRateSettings();
vehicle->requestDataStream(MAV_DATA_STREAM_EXTENDED_STATUS, 2);
vehicle->requestDataStream(MAV_DATA_STREAM_RC_CHANNELS, 2); struct StreamInfo_s {
vehicle->requestDataStream(MAV_DATA_STREAM_POSITION, 3); MAV_DATA_STREAM mavStream;
vehicle->requestDataStream(MAV_DATA_STREAM_EXTRA1, 10); int streamRate;
vehicle->requestDataStream(MAV_DATA_STREAM_EXTRA2, 10); };
vehicle->requestDataStream(MAV_DATA_STREAM_EXTRA3, 3);
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 ...@@ -733,22 +751,16 @@ QString APMFirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
switch (vehicleType) { switch (vehicleType) {
case MAV_TYPE_GENERIC: case MAV_TYPE_GENERIC:
return QStringLiteral(":/json/APM/MavCmdInfoCommon.json"); return QStringLiteral(":/json/APM/MavCmdInfoCommon.json");
break;
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
return QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json"); return QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json");
break;
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
return QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json"); return QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json");
break;
case MAV_TYPE_VTOL_QUADROTOR: case MAV_TYPE_VTOL_QUADROTOR:
return QStringLiteral(":/json/APM/MavCmdInfoVTOL.json"); return QStringLiteral(":/json/APM/MavCmdInfoVTOL.json");
break;
case MAV_TYPE_SUBMARINE: case MAV_TYPE_SUBMARINE:
return QStringLiteral(":/json/APM/MavCmdInfoSub.json"); return QStringLiteral(":/json/APM/MavCmdInfoSub.json");
break;
case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_GROUND_ROVER:
return QStringLiteral(":/json/APM/MavCmdInfoRover.json"); return QStringLiteral(":/json/APM/MavCmdInfoRover.json");
break;
default: default:
qWarning() << "APMFirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType; qWarning() << "APMFirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType;
return QString(); return QString();
......
...@@ -178,6 +178,15 @@ int QGroundControlQmlGlobal::supportedFirmwareCount() ...@@ -178,6 +178,15 @@ int QGroundControlQmlGlobal::supportedFirmwareCount()
return _firmwarePluginManager->supportedFirmwareTypes().count(); 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) bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPointF line2A, QPointF line2B)
{ {
......
...@@ -70,6 +70,8 @@ public: ...@@ -70,6 +70,8 @@ public:
Q_PROPERTY(bool taisyncSupported READ taisyncSupported CONSTANT) Q_PROPERTY(bool taisyncSupported READ taisyncSupported CONSTANT)
Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount 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 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 Q_PROPERTY(qreal zOrderWidgets READ zOrderWidgets CONSTANT) ///< z order value to widgets, for example: zoom controls, hud widgetss
...@@ -180,6 +182,8 @@ public: ...@@ -180,6 +182,8 @@ public:
int mavlinkSystemID () { return _toolbox->mavlinkProtocol()->getSystemId(); } int mavlinkSystemID () { return _toolbox->mavlinkProtocol()->getSystemId(); }
int supportedFirmwareCount (); int supportedFirmwareCount ();
bool px4ProFirmwareSupported ();
bool apmFirmwareSupported ();
bool skipSetupPage () { return _skipSetupPage; } bool skipSetupPage () { return _skipSetupPage; }
void setSkipSetupPage (bool skip); void setSkipSetupPage (bool skip);
......
{
"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
}
]
}
/****************************************************************************
*
* (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);
}
/****************************************************************************
*
* (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);
};
...@@ -201,10 +201,11 @@ ...@@ -201,10 +201,11 @@
"defaultValue": 0 "defaultValue": 0
}, },
{ {
"name": "apmStartMavlinkStreams", "name": "apmStartMavlinkStreams",
"shortDescription": "Request start of MAVLink telemetry streams (ArduPilot only)", "shortDescription": "Request start of MAVLink telemetry streams (ArduPilot only)",
"type": "bool", "type": "bool",
"defaultValue": true "defaultValue": true,
"qgcRebootRequired": true
}, },
{ {
"name": "enableTaisync", "name": "enableTaisync",
......
...@@ -17,15 +17,16 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -17,15 +17,16 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
, _airMapSettings (nullptr) , _airMapSettings (nullptr)
#endif #endif
, _appSettings (nullptr) , _appSettings (nullptr)
, _unitsSettings (nullptr) , _unitsSettings (nullptr)
, _autoConnectSettings (nullptr) , _autoConnectSettings (nullptr)
, _videoSettings (nullptr) , _videoSettings (nullptr)
, _flightMapSettings (nullptr) , _flightMapSettings (nullptr)
, _rtkSettings (nullptr) , _rtkSettings (nullptr)
, _flyViewSettings (nullptr) , _flyViewSettings (nullptr)
, _planViewSettings (nullptr) , _planViewSettings (nullptr)
, _brandImageSettings (nullptr) , _brandImageSettings (nullptr)
, _apmMavlinkStreamRateSettings (nullptr)
{ {
} }
...@@ -36,16 +37,17 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox) ...@@ -36,16 +37,17 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<SettingsManager>("QGroundControl.SettingsManager", 1, 0, "SettingsManager", "Reference only"); qmlRegisterUncreatableType<SettingsManager>("QGroundControl.SettingsManager", 1, 0, "SettingsManager", "Reference only");
_unitsSettings = new UnitsSettings (this); // Must be first since AppSettings references it _unitsSettings = new UnitsSettings (this); // Must be first since AppSettings references it
_appSettings = new AppSettings (this); _appSettings = new AppSettings (this);
_autoConnectSettings = new AutoConnectSettings (this); _autoConnectSettings = new AutoConnectSettings (this);
_videoSettings = new VideoSettings (this); _videoSettings = new VideoSettings (this);
_flightMapSettings = new FlightMapSettings (this); _flightMapSettings = new FlightMapSettings (this);
_rtkSettings = new RTKSettings (this); _rtkSettings = new RTKSettings (this);
_flyViewSettings = new FlyViewSettings (this); _flyViewSettings = new FlyViewSettings (this);
_planViewSettings = new PlanViewSettings (this); _planViewSettings = new PlanViewSettings (this);
_brandImageSettings = new BrandImageSettings (this); _brandImageSettings = new BrandImageSettings (this);
_apmMavlinkStreamRateSettings = new APMMavlinkStreamRateSettings (this);
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
_airMapSettings = new AirMapSettings (this); _airMapSettings = new AirMapSettings (this);
#endif #endif
} }
...@@ -23,6 +23,7 @@ ...@@ -23,6 +23,7 @@
#include "FlyViewSettings.h" #include "FlyViewSettings.h"
#include "PlanViewSettings.h" #include "PlanViewSettings.h"
#include "BrandImageSettings.h" #include "BrandImageSettings.h"
#include "APMMavlinkStreamRateSettings.h"
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
#include "AirMapSettings.h" #include "AirMapSettings.h"
#endif #endif
...@@ -37,17 +38,18 @@ public: ...@@ -37,17 +38,18 @@ public:
SettingsManager(QGCApplication* app, QGCToolbox* toolbox); SettingsManager(QGCApplication* app, QGCToolbox* toolbox);
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
Q_PROPERTY(QObject* airMapSettings READ airMapSettings CONSTANT) Q_PROPERTY(QObject* airMapSettings READ airMapSettings CONSTANT)
#endif #endif
Q_PROPERTY(QObject* appSettings READ appSettings CONSTANT) Q_PROPERTY(QObject* appSettings READ appSettings CONSTANT)
Q_PROPERTY(QObject* unitsSettings READ unitsSettings CONSTANT) Q_PROPERTY(QObject* unitsSettings READ unitsSettings CONSTANT)
Q_PROPERTY(QObject* autoConnectSettings READ autoConnectSettings CONSTANT) Q_PROPERTY(QObject* autoConnectSettings READ autoConnectSettings CONSTANT)
Q_PROPERTY(QObject* videoSettings READ videoSettings CONSTANT) Q_PROPERTY(QObject* videoSettings READ videoSettings CONSTANT)
Q_PROPERTY(QObject* flightMapSettings READ flightMapSettings CONSTANT) Q_PROPERTY(QObject* flightMapSettings READ flightMapSettings CONSTANT)
Q_PROPERTY(QObject* rtkSettings READ rtkSettings CONSTANT) Q_PROPERTY(QObject* rtkSettings READ rtkSettings CONSTANT)
Q_PROPERTY(QObject* flyViewSettings READ flyViewSettings CONSTANT) Q_PROPERTY(QObject* flyViewSettings READ flyViewSettings CONSTANT)
Q_PROPERTY(QObject* planViewSettings READ planViewSettings CONSTANT) Q_PROPERTY(QObject* planViewSettings READ planViewSettings CONSTANT)
Q_PROPERTY(QObject* brandImageSettings READ brandImageSettings CONSTANT) Q_PROPERTY(QObject* brandImageSettings READ brandImageSettings CONSTANT)
Q_PROPERTY(QObject* apmMavlinkStreamRateSettings READ apmMavlinkStreamRateSettings CONSTANT)
// Override from QGCTool // Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox); virtual void setToolbox(QGCToolbox *toolbox);
...@@ -55,29 +57,31 @@ public: ...@@ -55,29 +57,31 @@ public:
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
AirMapSettings* airMapSettings (void) { return _airMapSettings; } AirMapSettings* airMapSettings (void) { return _airMapSettings; }
#endif #endif
AppSettings* appSettings (void) { return _appSettings; } AppSettings* appSettings (void) { return _appSettings; }
UnitsSettings* unitsSettings (void) { return _unitsSettings; } UnitsSettings* unitsSettings (void) { return _unitsSettings; }
AutoConnectSettings* autoConnectSettings (void) { return _autoConnectSettings; } AutoConnectSettings* autoConnectSettings (void) { return _autoConnectSettings; }
VideoSettings* videoSettings (void) { return _videoSettings; } VideoSettings* videoSettings (void) { return _videoSettings; }
FlightMapSettings* flightMapSettings (void) { return _flightMapSettings; } FlightMapSettings* flightMapSettings (void) { return _flightMapSettings; }
RTKSettings* rtkSettings (void) { return _rtkSettings; } RTKSettings* rtkSettings (void) { return _rtkSettings; }
FlyViewSettings* flyViewSettings (void) { return _flyViewSettings; } FlyViewSettings* flyViewSettings (void) { return _flyViewSettings; }
PlanViewSettings* planViewSettings (void) { return _planViewSettings; } PlanViewSettings* planViewSettings (void) { return _planViewSettings; }
BrandImageSettings* brandImageSettings (void) { return _brandImageSettings; } BrandImageSettings* brandImageSettings (void) { return _brandImageSettings; }
APMMavlinkStreamRateSettings* apmMavlinkStreamRateSettings(void) { return _apmMavlinkStreamRateSettings; }
private: private:
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
AirMapSettings* _airMapSettings; AirMapSettings* _airMapSettings;
#endif #endif
AppSettings* _appSettings; AppSettings* _appSettings;
UnitsSettings* _unitsSettings; UnitsSettings* _unitsSettings;
AutoConnectSettings* _autoConnectSettings; AutoConnectSettings* _autoConnectSettings;
VideoSettings* _videoSettings; VideoSettings* _videoSettings;
FlightMapSettings* _flightMapSettings; FlightMapSettings* _flightMapSettings;
RTKSettings* _rtkSettings; RTKSettings* _rtkSettings;
FlyViewSettings* _flyViewSettings; FlyViewSettings* _flyViewSettings;
PlanViewSettings* _planViewSettings; PlanViewSettings* _planViewSettings;
BrandImageSettings* _brandImageSettings; BrandImageSettings* _brandImageSettings;
APMMavlinkStreamRateSettings* _apmMavlinkStreamRateSettings;
}; };
#endif #endif
...@@ -12,6 +12,7 @@ import QtQuick 2.3 ...@@ -12,6 +12,7 @@ import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4 import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2 import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.FactSystem 1.0 import QGroundControl.FactSystem 1.0
...@@ -33,6 +34,7 @@ Rectangle { ...@@ -33,6 +34,7 @@ Rectangle {
property bool _uploadedSelected: false property bool _uploadedSelected: false
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _showMavlinkLog: QGroundControl.corePlugin.options.showMavlinkLogOptions property var _showMavlinkLog: QGroundControl.corePlugin.options.showMavlinkLogOptions
property bool _showAPMStreamRates: QGroundControl.apmFirmwareSupported && QGroundControl.settingsManager.apmMavlinkStreamRateSettings.visible
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
...@@ -143,11 +145,6 @@ Rectangle { ...@@ -143,11 +145,6 @@ Rectangle {
} }
} }
FactCheckBox {
text: fact.shortDescription
fact: QGroundControl.settingsManager.appSettings.apmStartMavlinkStreams
}
QGCCheckBox { QGCCheckBox {
text: qsTr("Only accept MAVs with same protocol version") text: qsTr("Only accept MAVs with same protocol version")
checked: QGroundControl.isVersionCheckEnabled checked: QGroundControl.isVersionCheckEnabled
...@@ -158,6 +155,97 @@ Rectangle { ...@@ -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 //-- Mavlink Status
Item { Item {
width: __mavlinkRoot.width * 0.8 width: __mavlinkRoot.width * 0.8
...@@ -253,7 +341,7 @@ Rectangle { ...@@ -253,7 +341,7 @@ Rectangle {
visible: _showMavlinkLog visible: _showMavlinkLog
QGCLabel { QGCLabel {
id: mavlogLabel id: mavlogLabel
text: qsTr("MAVLink 2.0 Logging (PX4 Firmware Only)") text: qsTr("MAVLink 2.0 Logging (PX4 Pro Only)")
font.family: ScreenTools.demiboldFontFamily font.family: ScreenTools.demiboldFontFamily
} }
} }
...@@ -315,7 +403,7 @@ Rectangle { ...@@ -315,7 +403,7 @@ Rectangle {
visible: _showMavlinkLog visible: _showMavlinkLog
QGCLabel { QGCLabel {
id: logLabel 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 font.family: ScreenTools.demiboldFontFamily
} }
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment