18 changed files with 450 additions and 85 deletions
@ -0,0 +1,64 @@
@@ -0,0 +1,64 @@
|
||||
{ |
||||
"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 |
||||
} |
||||
] |
||||
} |
@ -0,0 +1,83 @@
@@ -0,0 +1,83 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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); |
||||
} |
@ -0,0 +1,42 @@
@@ -0,0 +1,42 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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); |
||||
}; |
Loading…
Reference in new issue