10 changed files with 614 additions and 0 deletions
@ -0,0 +1,122 @@ |
|||||||
|
{ |
||||||
|
"version": 1, |
||||||
|
"fileType": "FactMetaData", |
||||||
|
"QGC.MetaData.Facts": |
||||||
|
[ |
||||||
|
{ |
||||||
|
"name": "health", |
||||||
|
"shortDesc": "Health", |
||||||
|
"type": "int8" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "ecuIndex", |
||||||
|
"shortDesc": "Ecu Index", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "A" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "rpm", |
||||||
|
"shortDesc": "Rpm", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1 |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "fuelConsumed", |
||||||
|
"shortDesc": "Fuel Consumed", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "cm^3" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "fuelFlow", |
||||||
|
"shortDesc": "Fuel Flow", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "cm^3/min" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "engineLoad", |
||||||
|
"shortDesc": "Engine Load", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "%" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "throttlePos", |
||||||
|
"shortDesc": "Throttle Position", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "%" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "sparkTime", |
||||||
|
"shortDesc": "Spark dwell time", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "ms" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "baroPress", |
||||||
|
"shortDesc": "BarometricPressure", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "kPa" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "intakePress", |
||||||
|
"shortDesc": "Intake mainfold pressure", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "kPa" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "intakeTemp", |
||||||
|
"shortDesc": "Intake mainfold temperature", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "°C" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "cylinderTemp", |
||||||
|
"shortDesc": "Cylinder head temperature", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "°C" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "ignTime", |
||||||
|
"shortDesc": "Ignition Timing", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "deg" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "injTime", |
||||||
|
"shortDesc": "Injection Time", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "ms" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "exGasTemp", |
||||||
|
"shortDesc": "Exhaust gas Temperature", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "°C" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "throttleOut", |
||||||
|
"shortDesc": "Throttle Out", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "%" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "ptComp", |
||||||
|
"shortDesc": "Pt Compensation", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1 |
||||||
|
} |
||||||
|
] |
||||||
|
} |
@ -0,0 +1,77 @@ |
|||||||
|
{ |
||||||
|
"version": 1, |
||||||
|
"fileType": "FactMetaData", |
||||||
|
"QGC.MetaData.Facts": |
||||||
|
[ |
||||||
|
{ |
||||||
|
"name": "status", |
||||||
|
"shortDesc": "Status", |
||||||
|
"type": "uint64" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "genSpeed", |
||||||
|
"shortDesc": "Generator Speed", |
||||||
|
"type": "uint16", |
||||||
|
"units": "rpm" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "batteryCurrent", |
||||||
|
"shortDesc": "Battery Current", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "A" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "loadCurrent", |
||||||
|
"shortDesc": "Load Current", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "A" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "powerGenerated", |
||||||
|
"shortDesc": "Power Generated", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "W" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "busVoltage", |
||||||
|
"shortDesc": "Bus Voltage", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "V" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "rectifierTemp", |
||||||
|
"shortDesc": "Rectifier Temperature", |
||||||
|
"type": "int16", |
||||||
|
"units": "°C" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "batCurrentSetpoint", |
||||||
|
"shortDesc": "Battery Current Setpoint", |
||||||
|
"type": "float", |
||||||
|
"decimalPlaces": 1, |
||||||
|
"units": "A" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "genTemp", |
||||||
|
"shortDesc": "Generator Temperature", |
||||||
|
"type": "int16", |
||||||
|
"units": "°C" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "runtime", |
||||||
|
"shortDesc": "runtime", |
||||||
|
"type": "uint32", |
||||||
|
"units": "sec" |
||||||
|
}, |
||||||
|
{ |
||||||
|
"name": "timeMaintenance", |
||||||
|
"shortDesc": "Time until Maintenance", |
||||||
|
"type": "int32", |
||||||
|
"units": "sec" |
||||||
|
} |
||||||
|
] |
||||||
|
} |
@ -0,0 +1,114 @@ |
|||||||
|
#include "VehicleEFIFactGroup.h" |
||||||
|
#include "Vehicle.h" |
||||||
|
|
||||||
|
const char* VehicleEFIFactGroup::_healthFactName = "health"; |
||||||
|
const char* VehicleEFIFactGroup::_ecuIndexFactName = "ecuIndex"; |
||||||
|
const char* VehicleEFIFactGroup::_rpmFactName = "rpm"; |
||||||
|
const char* VehicleEFIFactGroup::_fuelConsumedFactName = "fuelConsumed"; |
||||||
|
const char* VehicleEFIFactGroup::_fuelFlowFactName = "fuelFlow"; |
||||||
|
const char* VehicleEFIFactGroup::_engineLoadFactName = "engineLoad"; |
||||||
|
const char* VehicleEFIFactGroup::_throttlePosFactName = "throttlePos"; |
||||||
|
const char* VehicleEFIFactGroup::_sparkTimeFactName = "sparkTime"; |
||||||
|
const char* VehicleEFIFactGroup::_baroPressFactName = "baroPress"; |
||||||
|
const char* VehicleEFIFactGroup::_intakePressFactName = "intakePress"; |
||||||
|
const char* VehicleEFIFactGroup::_intakeTempFactName = "intakeTemp"; |
||||||
|
const char* VehicleEFIFactGroup::_cylinderTempFactName = "cylinderTemp"; |
||||||
|
const char* VehicleEFIFactGroup::_ignTimeFactName = "ignTime"; |
||||||
|
const char* VehicleEFIFactGroup::_injTimeFactName = "injTime"; |
||||||
|
const char* VehicleEFIFactGroup::_exGasTempFactName = "exGasTemp"; |
||||||
|
const char* VehicleEFIFactGroup::_throttleOutFactName = "throttleOut"; |
||||||
|
const char* VehicleEFIFactGroup::_ptCompFactName = "ptComp"; |
||||||
|
|
||||||
|
|
||||||
|
VehicleEFIFactGroup::VehicleEFIFactGroup(QObject* parent) |
||||||
|
: FactGroup(1000, ":/json/Vehicle/EFIFact.json", parent) |
||||||
|
, _healthFact (0, _healthFactName, FactMetaData::valueTypeInt8) |
||||||
|
, _ecuIndexFact (0, _ecuIndexFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _rpmFact (0, _rpmFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _fuelConsumedFact (0, _fuelConsumedFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _fuelFlowFact (0, _fuelFlowFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _engineLoadFact (0, _engineLoadFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _throttlePosFact (0, _throttlePosFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _sparkTimeFact (0, _sparkTimeFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _baroPressFact (0, _baroPressFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _intakePressFact (0, _intakePressFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _intakeTempFact (0, _intakeTempFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _cylinderTempFact (0, _cylinderTempFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _ignTimeFact (0, _ignTimeFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _injTimeFact (0, _injTimeFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _exGasTempFact (0, _exGasTempFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _throttleOutFact (0, _throttleOutFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _ptCompFact (0, _ptCompFactName, FactMetaData::valueTypeFloat) |
||||||
|
{ |
||||||
|
_addFact(&_healthFact, _healthFactName); |
||||||
|
_addFact(&_ecuIndexFact, _ecuIndexFactName); |
||||||
|
_addFact(&_rpmFact, _rpmFactName); |
||||||
|
_addFact(&_fuelConsumedFact, _fuelConsumedFactName); |
||||||
|
_addFact(&_fuelFlowFact, _fuelFlowFactName); |
||||||
|
_addFact(&_engineLoadFact, _engineLoadFactName); |
||||||
|
_addFact(&_sparkTimeFact, _sparkTimeFactName); |
||||||
|
_addFact(&_throttlePosFact, _throttlePosFactName); |
||||||
|
_addFact(&_baroPressFact, _baroPressFactName); |
||||||
|
_addFact(&_intakePressFact, _intakePressFactName); |
||||||
|
_addFact(&_intakeTempFact, _intakeTempFactName); |
||||||
|
_addFact(&_cylinderTempFact, _cylinderTempFactName); |
||||||
|
_addFact(&_ignTimeFact, _ignTimeFactName); |
||||||
|
_addFact(&_exGasTempFact, _exGasTempFactName); |
||||||
|
_addFact(&_injTimeFact, _injTimeFactName); |
||||||
|
_addFact(&_throttleOutFact, _throttleOutFactName); |
||||||
|
_addFact(&_ptCompFact, _ptCompFactName); |
||||||
|
|
||||||
|
// Start out as not available "--.--"
|
||||||
|
_healthFact.setRawValue(qQNaN()); |
||||||
|
_ecuIndexFact.setRawValue(qQNaN()); |
||||||
|
_rpmFact.setRawValue(qQNaN()); |
||||||
|
_fuelConsumedFact.setRawValue(qQNaN()); |
||||||
|
_fuelFlowFact.setRawValue(qQNaN()); |
||||||
|
_engineLoadFact.setRawValue(qQNaN()); |
||||||
|
_sparkTimeFact.setRawValue(qQNaN()); |
||||||
|
_throttlePosFact.setRawValue(qQNaN()); |
||||||
|
_baroPressFact.setRawValue(qQNaN()); |
||||||
|
_intakePressFact.setRawValue(qQNaN()); |
||||||
|
_intakeTempFact.setRawValue(qQNaN()); |
||||||
|
_cylinderTempFact.setRawValue(qQNaN()); |
||||||
|
_ignTimeFact.setRawValue(qQNaN()); |
||||||
|
_exGasTempFact.setRawValue(qQNaN()); |
||||||
|
_injTimeFact.setRawValue(qQNaN()); |
||||||
|
_throttleOutFact.setRawValue(qQNaN()); |
||||||
|
_ptCompFact.setRawValue(qQNaN()); |
||||||
|
} |
||||||
|
|
||||||
|
void VehicleEFIFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& message) |
||||||
|
{ |
||||||
|
switch (message.msgid) { |
||||||
|
case MAVLINK_MSG_ID_EFI_STATUS: |
||||||
|
_handleEFIStatus(message); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void VehicleEFIFactGroup::_handleEFIStatus(mavlink_message_t& message) |
||||||
|
{ |
||||||
|
mavlink_efi_status_t efi; |
||||||
|
mavlink_msg_efi_status_decode(&message, &efi); |
||||||
|
|
||||||
|
health()->setRawValue (efi.health == INT8_MAX ? qQNaN() : efi.health); |
||||||
|
ecuIndex()->setRawValue (efi.ecu_index); |
||||||
|
rpm()->setRawValue (efi.rpm); |
||||||
|
fuelConsumed()->setRawValue (efi.fuel_consumed); |
||||||
|
fuelFlow()->setRawValue (efi.fuel_flow); |
||||||
|
engineLoad()->setRawValue (efi.engine_load); |
||||||
|
throttlePos()->setRawValue (efi.throttle_position); |
||||||
|
sparkTime()->setRawValue (efi.spark_dwell_time); |
||||||
|
baroPress()->setRawValue (efi.barometric_pressure); |
||||||
|
intakePress()->setRawValue (efi.intake_manifold_pressure); |
||||||
|
intakeTemp()->setRawValue (efi.intake_manifold_temperature); |
||||||
|
cylinderTemp()->setRawValue (efi.cylinder_head_temperature); |
||||||
|
ignTime()->setRawValue (efi.ignition_timing); |
||||||
|
injTime()->setRawValue (efi.injection_time); |
||||||
|
exGasTemp()->setRawValue (efi.exhaust_gas_temperature); |
||||||
|
throttleOut()->setRawValue (efi.throttle_out); |
||||||
|
ptComp()->setRawValue (efi.pt_compensation); |
||||||
|
} |
@ -0,0 +1,94 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include "FactGroup.h" |
||||||
|
#include "QGCMAVLink.h" |
||||||
|
|
||||||
|
class VehicleEFIFactGroup : public FactGroup |
||||||
|
{ |
||||||
|
Q_OBJECT |
||||||
|
|
||||||
|
public: |
||||||
|
VehicleEFIFactGroup(QObject* parent = nullptr); |
||||||
|
|
||||||
|
Q_PROPERTY(Fact* health READ health CONSTANT) |
||||||
|
Q_PROPERTY(Fact* ecuIndex READ ecuIndex CONSTANT) |
||||||
|
Q_PROPERTY(Fact* rpm READ rpm CONSTANT) |
||||||
|
Q_PROPERTY(Fact* fuelConsumed READ fuelConsumed CONSTANT) |
||||||
|
Q_PROPERTY(Fact* fuelFlow READ fuelFlow CONSTANT) |
||||||
|
Q_PROPERTY(Fact* engineLoad READ engineLoad CONSTANT) |
||||||
|
Q_PROPERTY(Fact* throttlePos READ throttlePos CONSTANT) |
||||||
|
Q_PROPERTY(Fact* sparkTime READ sparkTime CONSTANT) |
||||||
|
Q_PROPERTY(Fact* baroPress READ baroPress CONSTANT) |
||||||
|
Q_PROPERTY(Fact* intakePress READ intakePress CONSTANT) |
||||||
|
Q_PROPERTY(Fact* intakeTemp READ intakeTemp CONSTANT) |
||||||
|
Q_PROPERTY(Fact* cylinderTemp READ cylinderTemp CONSTANT) |
||||||
|
Q_PROPERTY(Fact* ignTime READ ignTime CONSTANT) |
||||||
|
Q_PROPERTY(Fact* injTime READ injTime CONSTANT) |
||||||
|
Q_PROPERTY(Fact* exGasTemp READ exGasTemp CONSTANT) |
||||||
|
Q_PROPERTY(Fact* throttleOut READ throttleOut CONSTANT) |
||||||
|
Q_PROPERTY(Fact* ptComp READ ptComp CONSTANT) |
||||||
|
Q_PROPERTY(Fact* ignVoltage READ ignVoltage CONSTANT) |
||||||
|
|
||||||
|
Fact* health () { return &_healthFact; } |
||||||
|
Fact* ecuIndex () { return &_ecuIndexFact; } |
||||||
|
Fact* rpm () { return &_rpmFact; } |
||||||
|
Fact* fuelConsumed () { return &_fuelConsumedFact; } |
||||||
|
Fact* fuelFlow () { return &_fuelFlowFact; } |
||||||
|
Fact* engineLoad () { return &_engineLoadFact; } |
||||||
|
Fact* throttlePos () { return &_throttlePosFact; } |
||||||
|
Fact* sparkTime () { return &_sparkTimeFact; } |
||||||
|
Fact* baroPress () { return &_baroPressFact; } |
||||||
|
Fact* intakePress () { return &_intakePressFact; } |
||||||
|
Fact* intakeTemp () { return &_intakeTempFact; } |
||||||
|
Fact* cylinderTemp () { return &_cylinderTempFact; } |
||||||
|
Fact* ignTime () { return &_ignTimeFact; } |
||||||
|
Fact* injTime () { return &_injTimeFact; } |
||||||
|
Fact* exGasTemp () { return &_exGasTempFact; } |
||||||
|
Fact* throttleOut () { return &_throttleOutFact; } |
||||||
|
Fact* ptComp () { return &_ptCompFact; } |
||||||
|
Fact* ignVoltage () { return &_ignVoltageFact; } |
||||||
|
|
||||||
|
// Overrides from FactGroup
|
||||||
|
virtual void handleMessage(Vehicle* vehicle, mavlink_message_t& message) override; |
||||||
|
|
||||||
|
static const char* _healthFactName; |
||||||
|
static const char* _ecuIndexFactName; |
||||||
|
static const char* _rpmFactName; |
||||||
|
static const char* _fuelConsumedFactName; |
||||||
|
static const char* _fuelFlowFactName; |
||||||
|
static const char* _engineLoadFactName; |
||||||
|
static const char* _throttlePosFactName; |
||||||
|
static const char* _sparkTimeFactName; |
||||||
|
static const char* _baroPressFactName; |
||||||
|
static const char* _intakePressFactName; |
||||||
|
static const char* _intakeTempFactName; |
||||||
|
static const char* _cylinderTempFactName; |
||||||
|
static const char* _ignTimeFactName; |
||||||
|
static const char* _injTimeFactName; |
||||||
|
static const char* _exGasTempFactName; |
||||||
|
static const char* _throttleOutFactName; |
||||||
|
static const char* _ptCompFactName; |
||||||
|
static const char* _ignVoltageFactName; |
||||||
|
|
||||||
|
protected: |
||||||
|
void _handleEFIStatus(mavlink_message_t& message); |
||||||
|
|
||||||
|
Fact _healthFact; |
||||||
|
Fact _ecuIndexFact; |
||||||
|
Fact _rpmFact; |
||||||
|
Fact _fuelConsumedFact; |
||||||
|
Fact _fuelFlowFact; |
||||||
|
Fact _engineLoadFact; |
||||||
|
Fact _throttlePosFact; |
||||||
|
Fact _sparkTimeFact; |
||||||
|
Fact _baroPressFact; |
||||||
|
Fact _intakePressFact; |
||||||
|
Fact _intakeTempFact; |
||||||
|
Fact _cylinderTempFact; |
||||||
|
Fact _ignTimeFact; |
||||||
|
Fact _injTimeFact; |
||||||
|
Fact _exGasTempFact; |
||||||
|
Fact _throttleOutFact; |
||||||
|
Fact _ptCompFact; |
||||||
|
Fact _ignVoltageFact; |
||||||
|
}; |
@ -0,0 +1,110 @@ |
|||||||
|
#include "VehicleGeneratorFactGroup.h" |
||||||
|
#include "Vehicle.h" |
||||||
|
#include <bitset> |
||||||
|
|
||||||
|
const char* VehicleGeneratorFactGroup::_statusFactName = "status"; |
||||||
|
const char* VehicleGeneratorFactGroup::_genSpeedFactName = "genSpeed"; |
||||||
|
const char* VehicleGeneratorFactGroup::_batteryCurrentFactName = "batteryCurrent"; |
||||||
|
const char* VehicleGeneratorFactGroup::_loadCurrentFactName = "loadCurrent"; |
||||||
|
const char* VehicleGeneratorFactGroup::_powerGeneratedFactName = "powerGenerated"; |
||||||
|
const char* VehicleGeneratorFactGroup::_busVoltageFactName = "busVoltage"; |
||||||
|
const char* VehicleGeneratorFactGroup::_rectifierTempFactName = "rectifierTemp"; |
||||||
|
const char* VehicleGeneratorFactGroup::_batCurrentSetpointFactName = "batCurrentSetpoint"; |
||||||
|
const char* VehicleGeneratorFactGroup::_genTempFactName = "genTemp"; |
||||||
|
const char* VehicleGeneratorFactGroup::_runtimeFactName = "runtime"; |
||||||
|
const char* VehicleGeneratorFactGroup::_timeMaintenanceFactName = "timeMaintenance"; |
||||||
|
|
||||||
|
VehicleGeneratorFactGroup::VehicleGeneratorFactGroup(QObject* parent) |
||||||
|
: FactGroup(1000, ":/json/Vehicle/GeneratorFact.json", parent) |
||||||
|
, _statusFact (0, _statusFactName, FactMetaData::valueTypeUint64) |
||||||
|
, _genSpeedFact (0, _genSpeedFactName, FactMetaData::valueTypeUint16) |
||||||
|
, _batteryCurrentFact (0, _batteryCurrentFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _loadCurrentFact (0, _loadCurrentFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _powerGeneratedFact (0, _powerGeneratedFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _busVoltageFact (0, _busVoltageFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _rectifierTempFact (0, _rectifierTempFactName, FactMetaData::valueTypeInt16) |
||||||
|
, _batCurrentSetpointFact (0, _batCurrentSetpointFactName, FactMetaData::valueTypeFloat) |
||||||
|
, _genTempFact (0, _genTempFactName, FactMetaData::valueTypeInt16) |
||||||
|
, _runtimeFact (0, _runtimeFactName, FactMetaData::valueTypeUint32) |
||||||
|
, _timeMaintenanceFact (0, _timeMaintenanceFactName, FactMetaData::valueTypeInt32) |
||||||
|
{ |
||||||
|
_addFact(&_statusFact, _statusFactName); |
||||||
|
_addFact(&_genSpeedFact, _genSpeedFactName); |
||||||
|
_addFact(&_batteryCurrentFact, _batteryCurrentFactName); |
||||||
|
_addFact(&_loadCurrentFact, _loadCurrentFactName); |
||||||
|
_addFact(&_powerGeneratedFact, _powerGeneratedFactName); |
||||||
|
_addFact(&_busVoltageFact, _busVoltageFactName); |
||||||
|
_addFact(&_batCurrentSetpointFact, _batCurrentSetpointFactName); |
||||||
|
_addFact(&_rectifierTempFact, _rectifierTempFactName); |
||||||
|
_addFact(&_genTempFact, _genTempFactName); |
||||||
|
_addFact(&_runtimeFact, _runtimeFactName); |
||||||
|
_addFact(&_timeMaintenanceFact, _timeMaintenanceFactName); |
||||||
|
|
||||||
|
// Start out as not available "--.--"
|
||||||
|
_statusFact.setRawValue(qQNaN()); |
||||||
|
_genSpeedFact.setRawValue(qQNaN()); |
||||||
|
_batteryCurrentFact.setRawValue(qQNaN()); |
||||||
|
_loadCurrentFact.setRawValue(qQNaN()); |
||||||
|
_powerGeneratedFact.setRawValue(qQNaN()); |
||||||
|
_busVoltageFact.setRawValue(qQNaN()); |
||||||
|
_batCurrentSetpointFact.setRawValue(qQNaN()); |
||||||
|
_rectifierTempFact.setRawValue(qQNaN()); |
||||||
|
_genTempFact.setRawValue(qQNaN()); |
||||||
|
_runtimeFact.setRawValue(qQNaN()); |
||||||
|
_timeMaintenanceFact.setRawValue(qQNaN()); |
||||||
|
} |
||||||
|
|
||||||
|
void VehicleGeneratorFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& message) |
||||||
|
{ |
||||||
|
switch (message.msgid) { |
||||||
|
case MAVLINK_MSG_ID_GENERATOR_STATUS: |
||||||
|
_handleGeneratorStatus(message); |
||||||
|
break; |
||||||
|
default: |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void VehicleGeneratorFactGroup::_handleGeneratorStatus(mavlink_message_t& message) |
||||||
|
{ |
||||||
|
mavlink_generator_status_t generator; |
||||||
|
mavlink_msg_generator_status_decode(&message, &generator); |
||||||
|
|
||||||
|
status()->setRawValue (generator.status == UINT16_MAX ? qQNaN() : generator.status); |
||||||
|
_updateGeneratorFlags(); |
||||||
|
genSpeed()->setRawValue (generator.generator_speed == UINT16_MAX ? qQNaN() : generator.generator_speed); |
||||||
|
batteryCurrent()->setRawValue (generator.battery_current); |
||||||
|
loadCurrent()->setRawValue (generator.load_current); |
||||||
|
powerGenerated()->setRawValue (generator.power_generated); |
||||||
|
busVoltage()->setRawValue (generator.bus_voltage); |
||||||
|
rectifierTemp()->setRawValue (generator.rectifier_temperature == INT16_MAX ? qQNaN() : generator.rectifier_temperature); |
||||||
|
batCurrentSetpoint()->setRawValue (generator.bat_current_setpoint); |
||||||
|
genTemp()->setRawValue (generator.generator_temperature == INT16_MAX ? qQNaN() : generator.generator_temperature); |
||||||
|
runtime()->setRawValue (generator.runtime == UINT32_MAX ? qQNaN() : generator.runtime); |
||||||
|
timeMaintenance()->setRawValue (generator.time_until_maintenance == INT32_MAX ? qQNaN() : generator.time_until_maintenance); |
||||||
|
} |
||||||
|
|
||||||
|
void VehicleGeneratorFactGroup::_updateGeneratorFlags() { |
||||||
|
|
||||||
|
// Check the status received, and convert it to a List with the state of each flag
|
||||||
|
int statusFlag = _statusFact.rawValue().toInt(); |
||||||
|
|
||||||
|
// No need to update the list if we have the same flags
|
||||||
|
if ( statusFlag == _prevFlag) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
_prevFlag = statusFlag; |
||||||
|
_flagsListGenerator.clear(); |
||||||
|
|
||||||
|
std::bitset<23> bitsetFlags(statusFlag); |
||||||
|
|
||||||
|
for (size_t i=0; i<bitsetFlags.size(); i++) { |
||||||
|
if (bitsetFlags.test(i)) { |
||||||
|
_flagsListGenerator.append(1); |
||||||
|
} else { |
||||||
|
_flagsListGenerator.append(0); |
||||||
|
} |
||||||
|
} |
||||||
|
emit flagsListGeneratorChanged(); |
||||||
|
} |
@ -0,0 +1,75 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include "FactGroup.h" |
||||||
|
#include "QGCMAVLink.h" |
||||||
|
|
||||||
|
class VehicleGeneratorFactGroup : public FactGroup |
||||||
|
{ |
||||||
|
Q_OBJECT |
||||||
|
|
||||||
|
public: |
||||||
|
VehicleGeneratorFactGroup(QObject* parent = nullptr); |
||||||
|
|
||||||
|
Q_PROPERTY(Fact* status READ status CONSTANT) |
||||||
|
Q_PROPERTY(Fact* genSpeed READ genSpeed CONSTANT) |
||||||
|
Q_PROPERTY(Fact* batteryCurrent READ batteryCurrent CONSTANT) |
||||||
|
Q_PROPERTY(Fact* loadCurrent READ loadCurrent CONSTANT) |
||||||
|
Q_PROPERTY(Fact* powerGenerated READ powerGenerated CONSTANT) |
||||||
|
Q_PROPERTY(Fact* busVoltage READ busVoltage CONSTANT) |
||||||
|
Q_PROPERTY(Fact* rectifierTemp READ rectifierTemp CONSTANT) |
||||||
|
Q_PROPERTY(Fact* batCurrentSetpoint READ batCurrentSetpoint CONSTANT) |
||||||
|
Q_PROPERTY(Fact* genTemp READ genTemp CONSTANT) |
||||||
|
Q_PROPERTY(Fact* runtime READ runtime CONSTANT) |
||||||
|
Q_PROPERTY(Fact* timeMaintenance READ timeMaintenance CONSTANT) |
||||||
|
Q_PROPERTY(QVariantList flagsListGenerator READ flagsListGenerator NOTIFY flagsListGeneratorChanged) |
||||||
|
|
||||||
|
Fact* status () { return &_statusFact; } |
||||||
|
Fact* genSpeed () { return &_genSpeedFact; } |
||||||
|
Fact* batteryCurrent () { return &_batteryCurrentFact; } |
||||||
|
Fact* loadCurrent () { return &_loadCurrentFact; } |
||||||
|
Fact* powerGenerated () { return &_powerGeneratedFact; } |
||||||
|
Fact* busVoltage () { return &_busVoltageFact; } |
||||||
|
Fact* rectifierTemp () { return &_rectifierTempFact; } |
||||||
|
Fact* batCurrentSetpoint () { return &_batCurrentSetpointFact; } |
||||||
|
Fact* genTemp () { return &_genTempFact; } |
||||||
|
Fact* runtime () { return &_runtimeFact; } |
||||||
|
Fact* timeMaintenance () { return &_timeMaintenanceFact; } |
||||||
|
QVariantList& flagsListGenerator() {return _flagsListGenerator; } |
||||||
|
|
||||||
|
// Overrides from FactGroup
|
||||||
|
virtual void handleMessage(Vehicle* vehicle, mavlink_message_t& message) override; |
||||||
|
|
||||||
|
static const char* _statusFactName; |
||||||
|
static const char* _genSpeedFactName; |
||||||
|
static const char* _batteryCurrentFactName; |
||||||
|
static const char* _loadCurrentFactName; |
||||||
|
static const char* _powerGeneratedFactName; |
||||||
|
static const char* _busVoltageFactName; |
||||||
|
static const char* _rectifierTempFactName; |
||||||
|
static const char* _batCurrentSetpointFactName; |
||||||
|
static const char* _genTempFactName; |
||||||
|
static const char* _runtimeFactName; |
||||||
|
static const char* _timeMaintenanceFactName; |
||||||
|
|
||||||
|
signals: |
||||||
|
void flagsListGeneratorChanged(); |
||||||
|
|
||||||
|
protected: |
||||||
|
void _handleGeneratorStatus(mavlink_message_t& message); |
||||||
|
void _updateGeneratorFlags(); |
||||||
|
|
||||||
|
Fact _statusFact; |
||||||
|
Fact _genSpeedFact; |
||||||
|
Fact _batteryCurrentFact; |
||||||
|
Fact _loadCurrentFact; |
||||||
|
Fact _powerGeneratedFact; |
||||||
|
Fact _busVoltageFact; |
||||||
|
Fact _rectifierTempFact; |
||||||
|
Fact _batCurrentSetpointFact; |
||||||
|
Fact _genTempFact; |
||||||
|
Fact _runtimeFact; |
||||||
|
Fact _timeMaintenanceFact; |
||||||
|
|
||||||
|
QVariantList _flagsListGenerator; |
||||||
|
int _prevFlag; |
||||||
|
}; |
Loading…
Reference in new issue