From 3f5aabfc1c70cb4a69448a9116bb8249fb62008a Mon Sep 17 00:00:00 2001 From: Dima Ponomarev <36133264+PonomarevDA@users.noreply.github.com> Date: Wed, 2 Sep 2020 19:37:49 +0300 Subject: [PATCH] Add Vehicle FactGroup for ESC_STATUS values (#8983) Add esc_status to vehicle fact group --- custom-example/qgroundcontrol.qrc | 1 + qgroundcontrol.pro | 2 + qgroundcontrol.qrc | 1 + src/Vehicle/EscStatusFactGroup.json | 106 +++++++++++++++++++++++ src/Vehicle/Vehicle.cc | 3 + src/Vehicle/Vehicle.h | 5 ++ src/Vehicle/VehicleEscStatusFactGroup.cc | 92 ++++++++++++++++++++ src/Vehicle/VehicleEscStatusFactGroup.h | 94 ++++++++++++++++++++ 8 files changed, 304 insertions(+) create mode 100644 src/Vehicle/EscStatusFactGroup.json create mode 100644 src/Vehicle/VehicleEscStatusFactGroup.cc create mode 100644 src/Vehicle/VehicleEscStatusFactGroup.h diff --git a/custom-example/qgroundcontrol.qrc b/custom-example/qgroundcontrol.qrc index f2c562c27..f49a138cd 100644 --- a/custom-example/qgroundcontrol.qrc +++ b/custom-example/qgroundcontrol.qrc @@ -316,6 +316,7 @@ ../src/Vehicle/BatteryFact.json ../src/Vehicle/ClockFact.json ../src/Vehicle/DistanceSensorFact.json + ../src/Vehicle/EscStatusFactGroup.json ../src/Vehicle/EstimatorStatusFactGroup.json ../src/Vehicle/GPSFact.json ../src/Vehicle/GPSRTKFact.json diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 8a0b3ddef..d2d0548a0 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -426,6 +426,7 @@ contains (DEFINES, QGC_ENABLE_PAIRING) { HEADERS += \ src/QmlControls/QmlUnitsConversion.h \ + src/Vehicle/VehicleEscStatusFactGroup.h \ src/api/QGCCorePlugin.h \ src/api/QGCOptions.h \ src/api/QGCSettings.h \ @@ -439,6 +440,7 @@ contains (DEFINES, QGC_ENABLE_PAIRING) { } SOURCES += \ + src/Vehicle/VehicleEscStatusFactGroup.cc \ src/api/QGCCorePlugin.cc \ src/api/QGCOptions.cc \ src/api/QGCSettings.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 05f627002..ea152f915 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -317,6 +317,7 @@ src/Vehicle/BatteryFact.json src/Vehicle/ClockFact.json src/Vehicle/DistanceSensorFact.json + src/Vehicle/EscStatusFactGroup.json src/Vehicle/EstimatorStatusFactGroup.json src/Vehicle/GPSFact.json src/Vehicle/GPSRTKFact.json diff --git a/src/Vehicle/EscStatusFactGroup.json b/src/Vehicle/EscStatusFactGroup.json new file mode 100644 index 000000000..81c681a76 --- /dev/null +++ b/src/Vehicle/EscStatusFactGroup.json @@ -0,0 +1,106 @@ +{ + "version": 1, + "fileType": "FactMetaData", + "QGC.MetaData.Facts": +[ +{ + "name": "index", + "shortDesc": "Index Of The First ESC In This Message", + "type": "uint8", + "default": 0 +}, +{ + "name": "rpmFirst", + "shortDesc": "Rotation Per Minute", + "type": "float", + "decimalPlaces": 2, + "default": null +}, +{ + "name": "rpmSecond", + "shortDesc": "Rotation Per Minute", + "type": "float", + "decimalPlaces": 2, + "default": null +}, +{ + "name": "rpmThird", + "shortDesc": "Rotation Per Minute", + "type": "float", + "decimalPlaces": 2, + "default": null +}, +{ + "name": "rpmFourth", + "shortDesc": "Rotation Per Minute", + "type": "float", + "decimalPlaces": 2, + "default": null +}, +{ + "name": "currentFirst", + "shortDesc": "Current", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "A" + +}, +{ + "name": "currentSecond", + "shortDesc": "Current", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "A" +}, +{ + "name": "currentThird", + "shortDesc": "Current", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "A" +}, +{ + "name": "currentFourth", + "shortDesc": "Current", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "A" +}, +{ + "name": "voltageFirst", + "shortDesc": "Voltage", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "v" +}, +{ + "name": "voltageSecond", + "shortDesc": "Voltage", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "v" +}, +{ + "name": "voltageThird", + "shortDesc": "Voltage", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "v" +}, +{ + "name": "voltageFourth", + "shortDesc": "Voltage", + "type": "float", + "decimalPlaces": 2, + "default": null, + "units": "v" +} +] +} diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 3423eae5e..788c0c551 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -92,6 +92,7 @@ const char* Vehicle::_vibrationFactGroupName = "vibration"; const char* Vehicle::_temperatureFactGroupName = "temperature"; const char* Vehicle::_clockFactGroupName = "clock"; const char* Vehicle::_distanceSensorFactGroupName = "distanceSensor"; +const char* Vehicle::_escStatusFactGroupName = "escStatus"; const char* Vehicle::_estimatorStatusFactGroupName = "estimatorStatus"; const char* Vehicle::_terrainFactGroupName = "terrain"; @@ -211,6 +212,7 @@ Vehicle::Vehicle(LinkInterface* link, , _temperatureFactGroup(this) , _clockFactGroup(this) , _distanceSensorFactGroup(this) + , _escStatusFactGroup(this) , _estimatorStatusFactGroup(this) , _terrainFactGroup(this) , _terrainProtocolHandler(new TerrainProtocolHandler(this, &_terrainFactGroup, this)) @@ -501,6 +503,7 @@ void Vehicle::_commonInit() _addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName); _addFactGroup(&_clockFactGroup, _clockFactGroupName); _addFactGroup(&_distanceSensorFactGroup, _distanceSensorFactGroupName); + _addFactGroup(&_escStatusFactGroup, _escStatusFactGroupName); _addFactGroup(&_estimatorStatusFactGroup, _estimatorStatusFactGroupName); _addFactGroup(&_terrainFactGroup, _terrainFactGroupName); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 53105167a..c6cb86e53 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -33,6 +33,7 @@ #include "VehicleSetpointFactGroup.h" #include "VehicleTemperatureFactGroup.h" #include "VehicleVibrationFactGroup.h" +#include "VehicleEscStatusFactGroup.h" #include "VehicleEstimatorStatusFactGroup.h" class UAS; @@ -279,6 +280,7 @@ public: Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT) Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT) Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT) + Q_PROPERTY(FactGroup* escStatus READ escStatusFactGroup CONSTANT) Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT) Q_PROPERTY(FactGroup* terrain READ terrainFactGroup CONSTANT) Q_PROPERTY(FactGroup* distanceSensors READ distanceSensorFactGroup CONSTANT) @@ -612,6 +614,7 @@ public: FactGroup* clockFactGroup () { return &_clockFactGroup; } FactGroup* setpointFactGroup () { return &_setpointFactGroup; } FactGroup* distanceSensorFactGroup () { return &_distanceSensorFactGroup; } + FactGroup* escStatusFactGroup () { return &_escStatusFactGroup; } FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; } FactGroup* terrainFactGroup () { return &_terrainFactGroup; } QmlObjectListModel* batteries () { return &_batteryFactGroupListModel; } @@ -1249,6 +1252,7 @@ private: VehicleClockFactGroup _clockFactGroup; VehicleSetpointFactGroup _setpointFactGroup; VehicleDistanceSensorFactGroup _distanceSensorFactGroup; + VehicleEscStatusFactGroup _escStatusFactGroup; VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup; TerrainFactGroup _terrainFactGroup; QmlObjectListModel _batteryFactGroupListModel; @@ -1282,6 +1286,7 @@ private: static const char* _temperatureFactGroupName; static const char* _clockFactGroupName; static const char* _distanceSensorFactGroupName; + static const char* _escStatusFactGroupName; static const char* _estimatorStatusFactGroupName; static const char* _terrainFactGroupName; diff --git a/src/Vehicle/VehicleEscStatusFactGroup.cc b/src/Vehicle/VehicleEscStatusFactGroup.cc new file mode 100644 index 000000000..1c5ab1024 --- /dev/null +++ b/src/Vehicle/VehicleEscStatusFactGroup.cc @@ -0,0 +1,92 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "VehicleEscStatusFactGroup.h" +#include "Vehicle.h" + +const char* VehicleEscStatusFactGroup::_indexFactName = "index"; + +const char* VehicleEscStatusFactGroup::_rpmFirstFactName = "rpm1"; +const char* VehicleEscStatusFactGroup::_rpmSecondFactName = "rpm2"; +const char* VehicleEscStatusFactGroup::_rpmThirdFactName = "rpm3"; +const char* VehicleEscStatusFactGroup::_rpmFourthFactName = "rpm4"; + +const char* VehicleEscStatusFactGroup::_currentFirstFactName = "current1"; +const char* VehicleEscStatusFactGroup::_currentSecondFactName = "current2"; +const char* VehicleEscStatusFactGroup::_currentThirdFactName = "current3"; +const char* VehicleEscStatusFactGroup::_currentFourthFactName = "current4"; + +const char* VehicleEscStatusFactGroup::_voltageFirstFactName = "voltage1"; +const char* VehicleEscStatusFactGroup::_voltageSecondFactName = "voltage2"; +const char* VehicleEscStatusFactGroup::_voltageThirdFactName = "voltage3"; +const char* VehicleEscStatusFactGroup::_voltageFourthFactName = "voltage4"; + +VehicleEscStatusFactGroup::VehicleEscStatusFactGroup(QObject* parent) + : FactGroup (1000, ":/json/Vehicle/EscStatusFactGroup.json", parent) + , _indexFact (0, _indexFactName, FactMetaData::valueTypeUint8) + + , _rpmFirstFact (0, _rpmFirstFactName, FactMetaData::valueTypeFloat) + , _rpmSecondFact (0, _rpmSecondFactName, FactMetaData::valueTypeFloat) + , _rpmThirdFact (0, _rpmThirdFactName, FactMetaData::valueTypeFloat) + , _rpmFourthFact (0, _rpmFourthFactName, FactMetaData::valueTypeFloat) + + , _currentFirstFact (0, _currentFirstFactName, FactMetaData::valueTypeFloat) + , _currentSecondFact (0, _currentSecondFactName, FactMetaData::valueTypeFloat) + , _currentThirdFact (0, _currentThirdFactName, FactMetaData::valueTypeFloat) + , _currentFourthFact (0, _currentFourthFactName, FactMetaData::valueTypeFloat) + + , _voltageFirstFact (0, _voltageFirstFactName, FactMetaData::valueTypeFloat) + , _voltageSecondFact (0, _voltageSecondFactName, FactMetaData::valueTypeFloat) + , _voltageThirdFact (0, _voltageThirdFactName, FactMetaData::valueTypeFloat) + , _voltageFourthFact (0, _voltageFourthFactName, FactMetaData::valueTypeFloat) +{ + _addFact(&_indexFact, _indexFactName); + + _addFact(&_rpmFirstFact, _rpmFirstFactName); + _addFact(&_rpmSecondFact, _rpmSecondFactName); + _addFact(&_rpmThirdFact, _rpmThirdFactName); + _addFact(&_rpmFourthFact, _rpmFourthFactName); + + _addFact(&_currentFirstFact, _currentFirstFactName); + _addFact(&_currentSecondFact, _currentSecondFactName); + _addFact(&_currentThirdFact, _currentThirdFactName); + _addFact(&_currentFourthFact, _currentFourthFactName); + + _addFact(&_voltageFirstFact, _voltageFirstFactName); + _addFact(&_voltageSecondFact, _voltageSecondFactName); + _addFact(&_voltageThirdFact, _voltageThirdFactName); + _addFact(&_voltageFourthFact, _voltageFourthFactName); +} + +void VehicleEscStatusFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& message) +{ + if (message.msgid != MAVLINK_MSG_ID_ESC_STATUS) { + return; + } + + mavlink_esc_status_t content; + mavlink_msg_esc_status_decode(&message, &content); + + index()->setRawValue (content.index); + + rpmFirst()->setRawValue (content.rpm[0]); + rpmSecond()->setRawValue (content.rpm[1]); + rpmThird()->setRawValue (content.rpm[2]); + rpmFourth()->setRawValue (content.rpm[3]); + + currentFirst()->setRawValue (content.current[0]); + currentSecond()->setRawValue (content.current[1]); + currentThird()->setRawValue (content.current[2]); + currentFourth()->setRawValue (content.current[3]); + + voltageFirst()->setRawValue (content.voltage[0]); + voltageSecond()->setRawValue (content.voltage[1]); + voltageThird()->setRawValue (content.voltage[2]); + voltageFourth()->setRawValue (content.voltage[3]); +} diff --git a/src/Vehicle/VehicleEscStatusFactGroup.h b/src/Vehicle/VehicleEscStatusFactGroup.h new file mode 100644 index 000000000..0c93917f6 --- /dev/null +++ b/src/Vehicle/VehicleEscStatusFactGroup.h @@ -0,0 +1,94 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "FactGroup.h" +#include "QGCMAVLink.h" + +class Vehicle; + +class VehicleEscStatusFactGroup : public FactGroup +{ + Q_OBJECT + +public: + VehicleEscStatusFactGroup(QObject* parent = nullptr); + + Q_PROPERTY(Fact* index READ index CONSTANT) + + Q_PROPERTY(Fact* rpmFirst READ rpmFirst CONSTANT) + Q_PROPERTY(Fact* rpmSecond READ rpmSecond CONSTANT) + Q_PROPERTY(Fact* rpmThird READ rpmThird CONSTANT) + Q_PROPERTY(Fact* rpmFourth READ rpmFourth CONSTANT) + + Q_PROPERTY(Fact* currentFirst READ currentFirst CONSTANT) + Q_PROPERTY(Fact* currentSecond READ currentSecond CONSTANT) + Q_PROPERTY(Fact* currentThird READ currentThird CONSTANT) + Q_PROPERTY(Fact* currentFourth READ currentFourth CONSTANT) + + Q_PROPERTY(Fact* voltageFirst READ voltageFirst CONSTANT) + Q_PROPERTY(Fact* voltageSecond READ voltageSecond CONSTANT) + Q_PROPERTY(Fact* voltageThird READ voltageThird CONSTANT) + Q_PROPERTY(Fact* voltageFourth READ voltageFourth CONSTANT) + + Fact* index () { return &_indexFact; } + + Fact* rpmFirst () { return &_rpmFirstFact; } + Fact* rpmSecond () { return &_rpmSecondFact; } + Fact* rpmThird () { return &_rpmThirdFact; } + Fact* rpmFourth () { return &_rpmFourthFact; } + + Fact* currentFirst () { return &_currentFirstFact; } + Fact* currentSecond () { return &_currentSecondFact; } + Fact* currentThird () { return &_currentThirdFact; } + Fact* currentFourth () { return &_currentFourthFact; } + + Fact* voltageFirst () { return &_voltageFirstFact; } + Fact* voltageSecond () { return &_voltageSecondFact; } + Fact* voltageThird () { return &_voltageThirdFact; } + Fact* voltageFourth () { return &_voltageFourthFact; } + + // Overrides from FactGroup + void handleMessage(Vehicle* vehicle, mavlink_message_t& message) override; + + static const char* _indexFactName; + + static const char* _rpmFirstFactName; + static const char* _rpmSecondFactName; + static const char* _rpmThirdFactName; + static const char* _rpmFourthFactName; + + static const char* _currentFirstFactName; + static const char* _currentSecondFactName; + static const char* _currentThirdFactName; + static const char* _currentFourthFactName; + + static const char* _voltageFirstFactName; + static const char* _voltageSecondFactName; + static const char* _voltageThirdFactName; + static const char* _voltageFourthFactName; +private: + Fact _indexFact; + + Fact _rpmFirstFact; + Fact _rpmSecondFact; + Fact _rpmThirdFact; + Fact _rpmFourthFact; + + Fact _currentFirstFact; + Fact _currentSecondFact; + Fact _currentThirdFact; + Fact _currentFourthFact; + + Fact _voltageFirstFact; + Fact _voltageSecondFact; + Fact _voltageThirdFact; + Fact _voltageFourthFact; +}; -- 2.22.0