8 changed files with 304 additions and 0 deletions
@ -0,0 +1,106 @@
@@ -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" |
||||
} |
||||
] |
||||
} |
@ -0,0 +1,92 @@
@@ -0,0 +1,92 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2020 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 "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]); |
||||
} |
@ -0,0 +1,94 @@
@@ -0,0 +1,94 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2020 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 "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; |
||||
}; |
Loading…
Reference in new issue