Commit 4e61315d authored by DonLakeFlyer's avatar DonLakeFlyer

parent d1a29a43
...@@ -705,6 +705,7 @@ HEADERS += \ ...@@ -705,6 +705,7 @@ HEADERS += \
src/Vehicle/TrajectoryPoints.h \ src/Vehicle/TrajectoryPoints.h \
src/Vehicle/Vehicle.h \ src/Vehicle/Vehicle.h \
src/Vehicle/VehicleObjectAvoidance.h \ src/Vehicle/VehicleObjectAvoidance.h \
src/Vehicle/VehicleBatteryFactGroup.h \
src/VehicleSetup/JoystickConfigController.h \ src/VehicleSetup/JoystickConfigController.h \
src/comm/LinkConfiguration.h \ src/comm/LinkConfiguration.h \
src/comm/LinkInterface.h \ src/comm/LinkInterface.h \
...@@ -924,6 +925,7 @@ SOURCES += \ ...@@ -924,6 +925,7 @@ SOURCES += \
src/Vehicle/TrajectoryPoints.cc \ src/Vehicle/TrajectoryPoints.cc \
src/Vehicle/Vehicle.cc \ src/Vehicle/Vehicle.cc \
src/Vehicle/VehicleObjectAvoidance.cc \ src/Vehicle/VehicleObjectAvoidance.cc \
src/Vehicle/VehicleBatteryFactGroup.cc \
src/VehicleSetup/JoystickConfigController.cc \ src/VehicleSetup/JoystickConfigController.cc \
src/comm/LinkConfiguration.cc \ src/comm/LinkConfiguration.cc \
src/comm/LinkInterface.cc \ src/comm/LinkInterface.cc \
......
...@@ -18,8 +18,6 @@ ...@@ -18,8 +18,6 @@
#include <QFile> #include <QFile>
#include <QQmlEngine> #include <QQmlEngine>
QGC_LOGGING_CATEGORY(FactGroupLog, "FactGroupLog")
FactGroup::FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent, bool ignoreCamelCase) FactGroup::FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent, bool ignoreCamelCase)
: QObject(parent) : QObject(parent)
, _updateRateMSecs(updateRateMsecs) , _updateRateMSecs(updateRateMsecs)
...@@ -135,6 +133,8 @@ void FactGroup::_addFact(Fact* fact, const QString& name) ...@@ -135,6 +133,8 @@ void FactGroup::_addFact(Fact* fact, const QString& name)
} }
_nameToFactMap[name] = fact; _nameToFactMap[name] = fact;
_factNames.append(name); _factNames.append(name);
emit factNamesChanged();
} }
void FactGroup::_addFactGroup(FactGroup* factGroup, const QString& name) void FactGroup::_addFactGroup(FactGroup* factGroup, const QString& name)
...@@ -145,6 +145,8 @@ void FactGroup::_addFactGroup(FactGroup* factGroup, const QString& name) ...@@ -145,6 +145,8 @@ void FactGroup::_addFactGroup(FactGroup* factGroup, const QString& name)
} }
_nameToFactGroupMap[name] = factGroup; _nameToFactGroupMap[name] = factGroup;
emit factGroupNamesChanged();
} }
void FactGroup::_updateAllValues(void) void FactGroup::_updateAllValues(void)
...@@ -175,3 +177,8 @@ QString FactGroup::_camelCase(const QString& text) ...@@ -175,3 +177,8 @@ QString FactGroup::_camelCase(const QString& text)
{ {
return text[0].toLower() + text.right(text.length() - 1); return text[0].toLower() + text.right(text.length() - 1);
} }
void FactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& /* message */)
{
// Default implementation does nothing
}
...@@ -7,18 +7,17 @@ ...@@ -7,18 +7,17 @@
* *
****************************************************************************/ ****************************************************************************/
#pragma once
#ifndef FactGroup_H
#define FactGroup_H
#include "Fact.h" #include "Fact.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include <QStringList> #include <QStringList>
#include <QMap> #include <QMap>
#include <QTimer> #include <QTimer>
Q_DECLARE_LOGGING_CATEGORY(VehicleLog) class Vehicle;
/// Used to group Facts together into an object hierarachy. /// Used to group Facts together into an object hierarachy.
class FactGroup : public QObject class FactGroup : public QObject
...@@ -29,8 +28,8 @@ public: ...@@ -29,8 +28,8 @@ public:
FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent = nullptr, bool ignoreCamelCase = false); FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent = nullptr, bool ignoreCamelCase = false);
FactGroup(int updateRateMsecs, QObject* parent = nullptr, bool ignoreCamelCase = false); FactGroup(int updateRateMsecs, QObject* parent = nullptr, bool ignoreCamelCase = false);
Q_PROPERTY(QStringList factNames READ factNames CONSTANT) Q_PROPERTY(QStringList factNames READ factNames NOTIFY factNamesChanged)
Q_PROPERTY(QStringList factGroupNames READ factGroupNames CONSTANT) Q_PROPERTY(QStringList factGroupNames READ factGroupNames NOTIFY factGroupNamesChanged)
/// @ return true: if the fact exists in the group /// @ return true: if the fact exists in the group
Q_INVOKABLE bool factExists(const QString& name); Q_INVOKABLE bool factExists(const QString& name);
...@@ -49,6 +48,13 @@ public: ...@@ -49,6 +48,13 @@ public:
QStringList factNames(void) const { return _factNames; } QStringList factNames(void) const { return _factNames; }
QStringList factGroupNames(void) const { return _nameToFactGroupMap.keys(); } QStringList factGroupNames(void) const { return _nameToFactGroupMap.keys(); }
/// Allows a FactGroup to parse incoming messages and fill in values
virtual void handleMessage(Vehicle* vehicle, mavlink_message_t& message);
signals:
void factNamesChanged (void);
void factGroupNamesChanged (void);
protected slots: protected slots:
virtual void _updateAllValues(void); virtual void _updateAllValues(void);
...@@ -71,5 +77,3 @@ private: ...@@ -71,5 +77,3 @@ private:
bool _ignoreCamelCase = false; bool _ignoreCamelCase = false;
QTimer _updateTimer; QTimer _updateTimer;
}; };
#endif
...@@ -52,13 +52,7 @@ void InstrumentValueData::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -52,13 +52,7 @@ void InstrumentValueData::_activeVehicleChanged(Vehicle* activeVehicle)
_activeVehicle = activeVehicle; _activeVehicle = activeVehicle;
_factGroupNames.clear(); emit factGroupNamesChanged();
_factGroupNames = _activeVehicle->factGroupNames();
for (QString& name: _factGroupNames) {
name[0] = name[0].toUpper();
}
_factGroupNames.prepend(vehicleFactGroupName);
emit factGroupNamesChanged(_factGroupNames);
if (_fact) { if (_fact) {
_fact = nullptr; _fact = nullptr;
...@@ -85,13 +79,11 @@ void InstrumentValueData::clearFact(void) ...@@ -85,13 +79,11 @@ void InstrumentValueData::clearFact(void)
{ {
_fact = nullptr; _fact = nullptr;
_factName.clear(); _factName.clear();
_factGroupName.clear();
_factValueNames.clear();
_text.clear(); _text.clear();
_icon.clear(); _icon.clear();
_showUnits = true; _showUnits = true;
emit factValueNamesChanged (_factValueNames); emit factValueNamesChanged ();
emit factChanged (_fact); emit factChanged (_fact);
emit factNameChanged (_factName); emit factNameChanged (_factName);
emit factGroupNameChanged (_factGroupName); emit factGroupNameChanged (_factGroupName);
...@@ -113,17 +105,12 @@ void InstrumentValueData::setFact(const QString& factGroupName, const QString& f ...@@ -113,17 +105,12 @@ void InstrumentValueData::setFact(const QString& factGroupName, const QString& f
} else { } else {
factGroup = _activeVehicle->getFactGroup(factGroupName); factGroup = _activeVehicle->getFactGroup(factGroupName);
} }
_factGroupName = factGroupName;
_factValueNames.clear();
_factValueNames = factGroup->factNames();
for (QString& name: _factValueNames) {
name[0] = name[0].toUpper();
}
QString nonEmptyFactName; QString nonEmptyFactName;
if (factGroup) { if (factGroup) {
if (factName.isEmpty()) { if (factName.isEmpty()) {
nonEmptyFactName = _factValueNames[0]; nonEmptyFactName = factValueNames()[0];
} else { } else {
nonEmptyFactName = factName; nonEmptyFactName = factName;
} }
...@@ -131,16 +118,14 @@ void InstrumentValueData::setFact(const QString& factGroupName, const QString& f ...@@ -131,16 +118,14 @@ void InstrumentValueData::setFact(const QString& factGroupName, const QString& f
} }
if (_fact) { if (_fact) {
_factGroupName = factGroupName; _factName = nonEmptyFactName;
_factName = nonEmptyFactName;
connect(_fact, &Fact::rawValueChanged, this, &InstrumentValueData::_updateRanges); connect(_fact, &Fact::rawValueChanged, this, &InstrumentValueData::_updateRanges);
} else { } else {
_factName.clear();
_factGroupName.clear(); _factGroupName.clear();
_factName.clear();
} }
emit factValueNamesChanged (_factValueNames); emit factValueNamesChanged ();
emit factChanged (_fact); emit factChanged (_fact);
emit factNameChanged (_factName); emit factNameChanged (_factName);
emit factGroupNameChanged (_factGroupName); emit factGroupNameChanged (_factGroupName);
...@@ -364,3 +349,32 @@ int InstrumentValueData::_currentRangeIndex(const QVariant& value) ...@@ -364,3 +349,32 @@ int InstrumentValueData::_currentRangeIndex(const QVariant& value)
} }
return _rangeValues.count(); return _rangeValues.count();
} }
QStringList InstrumentValueData::factGroupNames(void) const
{
QStringList groupNames = _activeVehicle->factGroupNames();
for (QString& name: groupNames) {
name[0] = name[0].toUpper();
}
groupNames.prepend(vehicleFactGroupName);
return groupNames;
}
QStringList InstrumentValueData::factValueNames(void) const
{
FactGroup* factGroup = nullptr;
if (_factGroupName == vehicleFactGroupName) {
factGroup = _activeVehicle;
} else {
factGroup = _activeVehicle->getFactGroup(_factGroupName);
}
QStringList valueNames = factGroup->factNames();
for (QString& name: valueNames) {
name[0] = name[0].toUpper();
}
return valueNames;
}
...@@ -33,8 +33,8 @@ public: ...@@ -33,8 +33,8 @@ public:
explicit InstrumentValueData(FactValueGrid* factValueGrid, QObject* parent); explicit InstrumentValueData(FactValueGrid* factValueGrid, QObject* parent);
Q_PROPERTY(FactValueGrid* factValueGrid MEMBER _factValueGrid CONSTANT) Q_PROPERTY(FactValueGrid* factValueGrid MEMBER _factValueGrid CONSTANT)
Q_PROPERTY(QStringList factGroupNames MEMBER _factGroupNames NOTIFY factGroupNamesChanged) Q_PROPERTY(QStringList factGroupNames READ factGroupNames NOTIFY factGroupNamesChanged)
Q_PROPERTY(QStringList factValueNames MEMBER _factValueNames NOTIFY factValueNamesChanged) Q_PROPERTY(QStringList factValueNames READ factValueNames NOTIFY factValueNamesChanged)
Q_PROPERTY(QString factGroupName READ factGroupName NOTIFY factGroupNameChanged) Q_PROPERTY(QString factGroupName READ factGroupName NOTIFY factGroupNameChanged)
Q_PROPERTY(QString factName READ factName NOTIFY factNameChanged) Q_PROPERTY(QString factName READ factName NOTIFY factNameChanged)
Q_PROPERTY(Fact* fact READ fact NOTIFY factChanged) Q_PROPERTY(Fact* fact READ fact NOTIFY factChanged)
...@@ -58,6 +58,8 @@ public: ...@@ -58,6 +58,8 @@ public:
Q_INVOKABLE void addRangeValue (void); Q_INVOKABLE void addRangeValue (void);
Q_INVOKABLE void removeRangeValue(int index); Q_INVOKABLE void removeRangeValue(int index);
QStringList factGroupNames (void) const;
QStringList factValueNames (void) const;
QString factGroupName (void) const { return _factGroupName; } QString factGroupName (void) const { return _factGroupName; }
QString factName (void) const { return _factName; } QString factName (void) const { return _factName; }
Fact* fact (void) { return _fact; } Fact* fact (void) { return _fact; }
...@@ -88,8 +90,8 @@ signals: ...@@ -88,8 +90,8 @@ signals:
void textChanged (QString text); void textChanged (QString text);
void showUnitsChanged (bool showUnits); void showUnitsChanged (bool showUnits);
void iconChanged (const QString& icon); void iconChanged (const QString& icon);
void factGroupNamesChanged (const QStringList& factGroupNames); void factGroupNamesChanged (void);
void factValueNamesChanged (const QStringList& factValueNames); void factValueNamesChanged (void);
void rangeTypeChanged (RangeType rangeType); void rangeTypeChanged (RangeType rangeType);
void rangeValuesChanged (const QVariantList& rangeValues); void rangeValuesChanged (const QVariantList& rangeValues);
void rangeColorsChanged (const QVariantList& rangeColors); void rangeColorsChanged (const QVariantList& rangeColors);
...@@ -119,8 +121,6 @@ private: ...@@ -119,8 +121,6 @@ private:
QString _text; QString _text;
bool _showUnits = true; bool _showUnits = true;
QString _icon; QString _icon;
QStringList _factGroupNames;
QStringList _factValueNames;
QColor _currentColor; QColor _currentColor;
double _currentOpacity = 1.0; double _currentOpacity = 1.0;
QString _currentIcon; QString _currentIcon;
......
...@@ -32,7 +32,7 @@ public: ...@@ -32,7 +32,7 @@ public:
DEFINE_SETTINGFACT(offlineEditingHoverSpeed) DEFINE_SETTINGFACT(offlineEditingHoverSpeed)
DEFINE_SETTINGFACT(offlineEditingAscentSpeed) DEFINE_SETTINGFACT(offlineEditingAscentSpeed)
DEFINE_SETTINGFACT(offlineEditingDescentSpeed) DEFINE_SETTINGFACT(offlineEditingDescentSpeed)
DEFINE_SETTINGFACT(batteryPercentRemainingAnnounce) DEFINE_SETTINGFACT(batteryPercentRemainingAnnounce) // Important: This is only used to calculate battery swaps
DEFINE_SETTINGFACT(defaultMissionItemAltitude) DEFINE_SETTINGFACT(defaultMissionItemAltitude)
DEFINE_SETTINGFACT(telemetrySave) DEFINE_SETTINGFACT(telemetrySave)
DEFINE_SETTINGFACT(telemetrySaveNotArmed) DEFINE_SETTINGFACT(telemetrySaveNotArmed)
......
{ {
"version": 1, "version": 1,
"fileType": "FactMetaData", "fileType": "FactMetaData",
"QGC.MetaData.Facts": "QGC.MetaData.Facts":
[ [
{
"name": "id",
"shortDesc": "Battery Id",
"type": "uint8"
},
{
"name": "batteryFunction",
"shortDesc": "Battery Function",
"type": "uint8",
"enumStrings": "n/a,All Flight Systems,Propulsion,Avionics,Payload",
"enumValues": "0,1,2,3,4",
"decimalPlaces": 0
},
{
"name": "batteryType",
"shortDesc": "Battery Type",
"type": "uint8",
"enumStrings": "n/a,LIPO,LIFE,LION,NIMH",
"enumValues": "0,1,2,3,4",
"decimalPlaces": 0
},
{ {
"name": "voltage", "name": "voltage",
"shortDesc": "Voltage", "shortDesc": "Voltage",
"type": "double", "type": "double",
"decimalPlaces": 2, "decimalPlaces": 2,
"units": "v" "units": "v"
}, },
{ {
"name": "percentRemaining", "name": "percentRemaining",
"shortDesc": "Percent", "shortDesc": "Percent",
"type": "double", "type": "double",
"decimalPlaces": 0, "decimalPlaces": 0,
"units": "%" "units": "%"
}, },
{ {
"name": "mahConsumed", "name": "mahConsumed",
"shortDesc": "Consumed", "shortDesc": "Consumed",
"type": "double", "type": "double",
"decimalPlaces": 0, "decimalPlaces": 0,
"units": "mAh" "units": "mAh"
}, },
{ {
"name": "current", "name": "current",
"shortDesc": "Current", "shortDesc": "Current",
"type": "double", "type": "double",
"decimalPlaces": 2, "decimalPlaces": 2,
"units": "A" "units": "A"
}, },
{ {
"name": "temperature", "name": "temperature",
"shortDesc": "Temperature", "shortDesc": "Temperature",
"type": "double", "type": "double",
"decimalPlaces": 0, "decimalPlaces": 0,
"units": "C" "units": "C"
}, },
{ {
"name": "instantPower", "name": "instantPower",
"shortDesc": "Watts", "shortDesc": "Watts",
"type": "double", "type": "double",
"decimalPlaces": 2, "decimalPlaces": 2,
"units": "W" "units": "W"
}, },
{ {
"name": "timeRemaining", "name": "timeRemaining",
"shortDesc": "Time Remaining", "shortDesc": "Time Remaining",
"type": "double", "type": "double",
"decimalPlaces": 0, "decimalPlaces": 0,
"units": "s" "units": "s"
}, },
{
"name": "timeRemainingStr",
"shortDesc": "Time Remaining",
"type": "string"
},
{ {
"name": "chargeState", "name": "chargeState",
"shortDesc": "Charge State", "shortDesc": "Charge State",
"type": "uint8", "type": "uint8",
"enumStrings": "n/a,Normal Operation,Low Battery State,Critical Battery State,Emergency Battery State,Battery Failed,Battery Unhealthy", "enumStrings": "n/a,Ok,Low,Critical,Emergency,Failed,Unhealthy,Charging",
"enumValues": "0,1,2,3,4,5,6", "enumValues": "0,1,2,3,4,5,6,7",
"decimalPlaces": 0 "decimalPlaces": 0
} }
] ]
......
This diff is collapsed.
...@@ -47,6 +47,7 @@ class TerrainProtocolHandler; ...@@ -47,6 +47,7 @@ class TerrainProtocolHandler;
class ComponentInformationManager; class ComponentInformationManager;
class FTPManager; class FTPManager;
class InitialConnectStateMachine; class InitialConnectStateMachine;
class VehicleBatteryFactGroup;
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager; class AirspaceVehicleManager;
...@@ -257,53 +258,6 @@ private: ...@@ -257,53 +258,6 @@ private:
Fact _lockFact; Fact _lockFact;
}; };
class VehicleBatteryFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleBatteryFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* voltage READ voltage CONSTANT)
Q_PROPERTY(Fact* percentRemaining READ percentRemaining CONSTANT)
Q_PROPERTY(Fact* mahConsumed READ mahConsumed CONSTANT)
Q_PROPERTY(Fact* current READ current CONSTANT)
Q_PROPERTY(Fact* temperature READ temperature CONSTANT)
Q_PROPERTY(Fact* instantPower READ instantPower CONSTANT)
Q_PROPERTY(Fact* timeRemaining READ timeRemaining CONSTANT)
Q_PROPERTY(Fact* chargeState READ chargeState CONSTANT)
Fact* voltage () { return &_voltageFact; }
Fact* percentRemaining () { return &_percentRemainingFact; }
Fact* mahConsumed () { return &_mahConsumedFact; }
Fact* current () { return &_currentFact; }
Fact* temperature () { return &_temperatureFact; }
Fact* instantPower () { return &_instantPowerFact; }
Fact* timeRemaining () { return &_timeRemainingFact; }
Fact* chargeState () { return &_chargeStateFact; }
static const char* _voltageFactName;
static const char* _percentRemainingFactName;
static const char* _mahConsumedFactName;
static const char* _currentFactName;
static const char* _temperatureFactName;
static const char* _instantPowerFactName;
static const char* _timeRemainingFactName;
static const char* _chargeStateFactName;
static const char* _settingsGroup;
private:
Fact _voltageFact;
Fact _percentRemainingFact;
Fact _mahConsumedFact;
Fact _currentFact;
Fact _temperatureFact;
Fact _instantPowerFact;
Fact _timeRemainingFact;
Fact _chargeStateFact;
};
class VehicleTemperatureFactGroup : public FactGroup class VehicleTemperatureFactGroup : public FactGroup
{ {
Q_OBJECT Q_OBJECT
...@@ -692,17 +646,16 @@ public: ...@@ -692,17 +646,16 @@ public:
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT) Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
Q_PROPERTY(Fact* throttlePct READ throttlePct CONSTANT) Q_PROPERTY(Fact* throttlePct READ throttlePct CONSTANT)
Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT) Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery READ battery1FactGroup CONSTANT) Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery2 READ battery2FactGroup CONSTANT) Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT) Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT) Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT) Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT)
Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT) Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT)
Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT) Q_PROPERTY(FactGroup* terrain READ terrainFactGroup CONSTANT)
Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT) Q_PROPERTY(FactGroup* distanceSensors READ distanceSensorFactGroup CONSTANT)
Q_PROPERTY(FactGroup* terrain READ terrainFactGroup CONSTANT) Q_PROPERTY(QmlObjectListModel* batteries READ batteries CONSTANT)
Q_PROPERTY(FactGroup* distanceSensors READ distanceSensorFactGroup CONSTANT)
Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged) Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged) Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
...@@ -720,7 +673,7 @@ public: ...@@ -720,7 +673,7 @@ public:
Q_INVOKABLE void resetCounters (); Q_INVOKABLE void resetCounters ();
// Called when the message drop-down is invoked to clear current count // Called when the message drop-down is invoked to clear current count
Q_INVOKABLE void resetMessages(); Q_INVOKABLE void resetMessages();
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust); Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Q_INVOKABLE void disconnectInactiveVehicle(); Q_INVOKABLE void disconnectInactiveVehicle();
...@@ -1027,8 +980,6 @@ public: ...@@ -1027,8 +980,6 @@ public:
Fact* throttlePct () { return &_throttlePctFact; } Fact* throttlePct () { return &_throttlePctFact; }
FactGroup* gpsFactGroup () { return &_gpsFactGroup; } FactGroup* gpsFactGroup () { return &_gpsFactGroup; }
FactGroup* battery1FactGroup () { return &_battery1FactGroup; }
FactGroup* battery2FactGroup () { return &_battery2FactGroup; }
FactGroup* windFactGroup () { return &_windFactGroup; } FactGroup* windFactGroup () { return &_windFactGroup; }
FactGroup* vibrationFactGroup () { return &_vibrationFactGroup; } FactGroup* vibrationFactGroup () { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup () { return &_temperatureFactGroup; } FactGroup* temperatureFactGroup () { return &_temperatureFactGroup; }
...@@ -1037,6 +988,7 @@ public: ...@@ -1037,6 +988,7 @@ public:
FactGroup* distanceSensorFactGroup () { return &_distanceSensorFactGroup; } FactGroup* distanceSensorFactGroup () { return &_distanceSensorFactGroup; }
FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; } FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; }
FactGroup* terrainFactGroup () { return &_terrainFactGroup; } FactGroup* terrainFactGroup () { return &_terrainFactGroup; }
QmlObjectListModel* batteries () { return &_batteryFactGroupListModel; }
void setConnectionLostEnabled(bool connectionLostEnabled); void setConnectionLostEnabled(bool connectionLostEnabled);
...@@ -1404,7 +1356,6 @@ private: ...@@ -1404,7 +1356,6 @@ private:
void _writeCsvLine (); void _writeCsvLine ();
void _flightTimerStart (); void _flightTimerStart ();
void _flightTimerStop (); void _flightTimerStop ();
void _batteryStatusWorker (int batteryId, double voltage, double current, double batteryRemainingPct);
void _chunkedStatusTextTimeout (void); void _chunkedStatusTextTimeout (void);
void _chunkedStatusTextCompleted (uint8_t compId); void _chunkedStatusTextCompleted (uint8_t compId);
...@@ -1566,9 +1517,6 @@ private: ...@@ -1566,9 +1517,6 @@ private:
QString _gitHash; QString _gitHash;
quint64 _uid; quint64 _uid;
QElapsedTimer _lastBatteryAnnouncement;
int _lastAnnouncedLowBatteryPercent;
SharedLinkInterfacePointer _priorityLink; // We always keep a reference to the priority link to manage shutdown ordering SharedLinkInterfacePointer _priorityLink; // We always keep a reference to the priority link to manage shutdown ordering
bool _priorityLinkCommanded; bool _priorityLinkCommanded;
...@@ -1653,6 +1601,8 @@ private: ...@@ -1653,6 +1601,8 @@ private:
void _sendMavCommandWorker(bool commandInt, bool requestMessage, bool showError, MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, float param5, float param6, float param7); void _sendMavCommandWorker(bool commandInt, bool requestMessage, bool showError, MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, float param5, float param6, float param7);
QMap<uint8_t /* batteryId */, uint8_t /* MAV_BATTERY_CHARGE_STATE_OK */> _lowestBatteryChargeStateAnnouncedMap;
// FactGroup facts // FactGroup facts
Fact _rollFact; Fact _rollFact;
...@@ -1677,8 +1627,6 @@ private: ...@@ -1677,8 +1627,6 @@ private:
Fact _throttlePctFact; Fact _throttlePctFact;
VehicleGPSFactGroup _gpsFactGroup; VehicleGPSFactGroup _gpsFactGroup;
VehicleBatteryFactGroup _battery1FactGroup;
VehicleBatteryFactGroup _battery2FactGroup;
VehicleWindFactGroup _windFactGroup; VehicleWindFactGroup _windFactGroup;
VehicleVibrationFactGroup _vibrationFactGroup; VehicleVibrationFactGroup _vibrationFactGroup;
VehicleTemperatureFactGroup _temperatureFactGroup; VehicleTemperatureFactGroup _temperatureFactGroup;
...@@ -1687,6 +1635,7 @@ private: ...@@ -1687,6 +1635,7 @@ private:
VehicleDistanceSensorFactGroup _distanceSensorFactGroup; VehicleDistanceSensorFactGroup _distanceSensorFactGroup;
VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup; VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
TerrainFactGroup _terrainFactGroup; TerrainFactGroup _terrainFactGroup;
QmlObjectListModel _batteryFactGroupListModel;
TerrainProtocolHandler* _terrainProtocolHandler = nullptr; TerrainProtocolHandler* _terrainProtocolHandler = nullptr;
...@@ -1712,8 +1661,6 @@ private: ...@@ -1712,8 +1661,6 @@ private:
static const char* _throttlePctFactName; static const char* _throttlePctFactName;
static const char* _gpsFactGroupName; static const char* _gpsFactGroupName;
static const char* _battery1FactGroupName;
static const char* _battery2FactGroupName;
static const char* _windFactGroupName; static const char* _windFactGroupName;
static const char* _vibrationFactGroupName; static const char* _vibrationFactGroupName;
static const char* _temperatureFactGroupName; static const char* _temperatureFactGroupName;
...@@ -1729,4 +1676,5 @@ private: ...@@ -1729,4 +1676,5 @@ private:
static const char* _joystickEnabledSettingsKey; static const char* _joystickEnabledSettingsKey;
friend class InitialConnectStateMachine; friend class InitialConnectStateMachine;
friend class VehicleBatteryFactGroup; // Allow VehicleBatteryFactGroup to call _addFactGroup
}; };
/****************************************************************************
*
* (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 "VehicleBatteryFactGroup.h"
#include "QmlObjectListModel.h"
#include "Vehicle.h"
const char* VehicleBatteryFactGroup::_batteryFactGroupNamePrefix = "battery";
const char* VehicleBatteryFactGroup::_batteryIdFactName = "id";
const char* VehicleBatteryFactGroup::_batteryFunctionFactName = "batteryFunction";
const char* VehicleBatteryFactGroup::_batteryTypeFactName = "batteryType";
const char* VehicleBatteryFactGroup::_voltageFactName = "voltage";
const char* VehicleBatteryFactGroup::_percentRemainingFactName = "percentRemaining";
const char* VehicleBatteryFactGroup::_mahConsumedFactName = "mahConsumed";
const char* VehicleBatteryFactGroup::_currentFactName = "current";
const char* VehicleBatteryFactGroup::_temperatureFactName = "temperature";
const char* VehicleBatteryFactGroup::_instantPowerFactName = "instantPower";
const char* VehicleBatteryFactGroup::_timeRemainingFactName = "timeRemaining";
const char* VehicleBatteryFactGroup::_timeRemainingStrFactName = "timeRemainingStr";
const char* VehicleBatteryFactGroup::_chargeStateFactName = "chargeState";
const char* VehicleBatteryFactGroup::_settingsGroup = "Vehicle.battery";
VehicleBatteryFactGroup::VehicleBatteryFactGroup(uint8_t batteryId, QObject* parent)
: FactGroup (1000, ":/json/Vehicle/BatteryFact.json", parent)
, _batteryIdFact (0, _batteryIdFactName, FactMetaData::valueTypeUint8)
, _batteryFunctionFact (0, _batteryFunctionFactName, FactMetaData::valueTypeUint8)
, _batteryTypeFact (0, _batteryTypeFactName, FactMetaData::valueTypeUint8)
, _voltageFact (0, _voltageFactName, FactMetaData::valueTypeDouble)
, _currentFact (0, _currentFactName, FactMetaData::valueTypeDouble)
, _mahConsumedFact (0, _mahConsumedFactName, FactMetaData::valueTypeDouble)
, _temperatureFact (0, _temperatureFactName, FactMetaData::valueTypeDouble)
, _percentRemainingFact (0, _percentRemainingFactName, FactMetaData::valueTypeDouble)
, _timeRemainingFact (0, _timeRemainingFactName, FactMetaData::valueTypeDouble)
, _timeRemainingStrFact (0, _timeRemainingStrFactName, FactMetaData::valueTypeString)
, _chargeStateFact (0, _chargeStateFactName, FactMetaData::valueTypeUint8)
, _instantPowerFact (0, _instantPowerFactName, FactMetaData::valueTypeDouble)
{
_addFact(&_batteryIdFact, _batteryIdFactName);
_addFact(&_batteryFunctionFact, _batteryFunctionFactName);
_addFact(&_batteryTypeFact, _batteryTypeFactName);
_addFact(&_voltageFact, _voltageFactName);
_addFact(&_currentFact, _currentFactName);
_addFact(&_mahConsumedFact, _mahConsumedFactName);
_addFact(&_temperatureFact, _temperatureFactName);
_addFact(&_percentRemainingFact, _percentRemainingFactName);
_addFact(&_timeRemainingFact, _timeRemainingFactName);
_addFact(&_timeRemainingStrFact, _timeRemainingStrFactName);
_addFact(&_chargeStateFact, _chargeStateFactName);
_addFact(&_instantPowerFact, _instantPowerFactName);
_batteryIdFact.setRawValue (batteryId);
_batteryFunctionFact.setRawValue (MAV_BATTERY_FUNCTION_UNKNOWN);
_batteryTypeFact.setRawValue (MAV_BATTERY_TYPE_UNKNOWN);
_voltageFact.setRawValue (qQNaN());
_currentFact.setRawValue (qQNaN());
_mahConsumedFact.setRawValue (qQNaN());
_temperatureFact.setRawValue (qQNaN());
_percentRemainingFact.setRawValue (qQNaN());
_timeRemainingFact.setRawValue (qQNaN());
_chargeStateFact.setRawValue (MAV_BATTERY_CHARGE_STATE_UNDEFINED);
_instantPowerFact.setRawValue (qQNaN());
connect(&_timeRemainingFact, &Fact::rawValueChanged, this, &VehicleBatteryFactGroup::_timeRemainingChanged);
}
void VehicleBatteryFactGroup::handleMessageForFactGroupCreation(Vehicle* vehicle, mavlink_message_t& message)
{
switch (message.msgid) {
case MAVLINK_MSG_ID_HIGH_LATENCY:
case MAVLINK_MSG_ID_HIGH_LATENCY2:
_findOrAddBatteryGroupById(vehicle, 0);
break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
{
mavlink_battery_status_t batteryStatus;
mavlink_msg_battery_status_decode(&message, &batteryStatus);
_findOrAddBatteryGroupById(vehicle, batteryStatus.id);
}
break;
}
}
void VehicleBatteryFactGroup::handleMessage(Vehicle* vehicle, mavlink_message_t& message)
{
switch (message.msgid) {
case MAVLINK_MSG_ID_HIGH_LATENCY:
_handleHighLatency(vehicle, message);
break;
case MAVLINK_MSG_ID_HIGH_LATENCY2:
_handleHighLatency2(vehicle, message);
break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
_handleBatteryStatus(vehicle, message);
break;
}
}
void VehicleBatteryFactGroup::_handleHighLatency(Vehicle* vehicle, mavlink_message_t& message)
{
mavlink_high_latency_t highLatency;
mavlink_msg_high_latency_decode(&message, &highLatency);
VehicleBatteryFactGroup* group = _findOrAddBatteryGroupById(vehicle, 0);
group->percentRemaining()->setRawValue(highLatency.battery_remaining == UINT8_MAX ? qQNaN() : highLatency.battery_remaining);
}
void VehicleBatteryFactGroup::_handleHighLatency2(Vehicle* vehicle, mavlink_message_t& message)
{
mavlink_high_latency2_t highLatency2;
mavlink_msg_high_latency2_decode(&message, &highLatency2);
VehicleBatteryFactGroup* group = _findOrAddBatteryGroupById(vehicle, 0);
group->percentRemaining()->setRawValue(highLatency2.battery == -1 ? qQNaN() : highLatency2.battery);
}
void VehicleBatteryFactGroup::_handleBatteryStatus(Vehicle* vehicle, mavlink_message_t& message)
{
mavlink_battery_status_t batteryStatus;
mavlink_msg_battery_status_decode(&message, &batteryStatus);
VehicleBatteryFactGroup* group = _findOrAddBatteryGroupById(vehicle, batteryStatus.id);
double totalVoltage = qQNaN();
for (int i=0; i<10; i++) {
double cellVoltage = batteryStatus.voltages[i] == UINT16_MAX ? qQNaN() : static_cast<double>(batteryStatus.voltages[i]) / 1000.0;
if (qIsNaN(cellVoltage)) {
break;
}
if (i == 0) {
totalVoltage = cellVoltage;
} else {
totalVoltage += cellVoltage;
}
}
group->function()->setRawValue (batteryStatus.battery_function);
group->type()->setRawValue (batteryStatus.type);
group->temperature()->setRawValue (batteryStatus.temperature == INT16_MAX ? qQNaN() : static_cast<double>(batteryStatus.temperature) / 100.0);
group->voltage()->setRawValue (totalVoltage);
group->current()->setRawValue (batteryStatus.current_battery == -1 ? qQNaN() : batteryStatus.current_battery);
group->mahConsumed()->setRawValue (batteryStatus.current_consumed == -1 ? qQNaN() : batteryStatus.current_consumed);
group->percentRemaining()->setRawValue (batteryStatus.battery_remaining == -1 ? qQNaN() : batteryStatus.battery_remaining);
group->timeRemaining()->setRawValue (batteryStatus.time_remaining == 0 ? qQNaN() : batteryStatus.time_remaining);
group->chargeState()->setRawValue (batteryStatus.charge_state);
group->instantPower()->setRawValue (totalVoltage * group->current()->rawValue().toDouble());
}
VehicleBatteryFactGroup* VehicleBatteryFactGroup::_findOrAddBatteryGroupById(Vehicle* vehicle, uint8_t batteryId)
{
QmlObjectListModel* batteries = vehicle->batteries();
// We maintain the list in order sorted by battery id so the ui shows them sorted.
for (int i=0; i<batteries->count(); i++) {
VehicleBatteryFactGroup* group = batteries->value<VehicleBatteryFactGroup*>(i);
int listBatteryId = group->id()->rawValue().toInt();
if (listBatteryId > batteryId) {
VehicleBatteryFactGroup* newBatteryGroup = new VehicleBatteryFactGroup(batteryId, batteries);
batteries->insert(i, newBatteryGroup);
vehicle->_addFactGroup(newBatteryGroup, QStringLiteral("%1%2").arg(_batteryFactGroupNamePrefix).arg(batteryId));
return newBatteryGroup;
} else if (listBatteryId == batteryId) {
return group;
}
}
VehicleBatteryFactGroup* newBatteryGroup = new VehicleBatteryFactGroup(batteryId, batteries);
batteries->append(newBatteryGroup);
vehicle->_addFactGroup(newBatteryGroup, QStringLiteral("%1%2").arg(_batteryFactGroupNamePrefix).arg(batteryId));
return newBatteryGroup;
}
void VehicleBatteryFactGroup::_timeRemainingChanged(QVariant value)
{
if (qIsNaN(value.toDouble())) {
_timeRemainingStrFact.setRawValue("--:--:--");
} else {
int totalSeconds = value.toInt();
int hours = totalSeconds / 3600;
int minutes = (totalSeconds % 3600) / 60;
int seconds = totalSeconds % 60;
_timeRemainingStrFact.setRawValue(QString::asprintf("%02dH:%02dM:%02dS", hours, minutes, seconds));
}
}
/****************************************************************************
*
* (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 VehicleBatteryFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleBatteryFactGroup(uint8_t batteryId, QObject* parent = nullptr);
Q_PROPERTY(Fact* id READ id CONSTANT)
Q_PROPERTY(Fact* function READ function CONSTANT)
Q_PROPERTY(Fact* type READ type CONSTANT)
Q_PROPERTY(Fact* temperature READ temperature CONSTANT)
Q_PROPERTY(Fact* voltage READ voltage CONSTANT)
Q_PROPERTY(Fact* current READ current CONSTANT)
Q_PROPERTY(Fact* mahConsumed READ mahConsumed CONSTANT)
Q_PROPERTY(Fact* percentRemaining READ percentRemaining CONSTANT)
Q_PROPERTY(Fact* timeRemaining READ timeRemaining CONSTANT)
Q_PROPERTY(Fact* timeRemainingStr READ timeRemainingStr CONSTANT)
Q_PROPERTY(Fact* chargeState READ chargeState CONSTANT)
Q_PROPERTY(Fact* instantPower READ instantPower CONSTANT)
Fact* id () { return &_batteryIdFact; }
Fact* function () { return &_batteryFunctionFact; }
Fact* type () { return &_batteryTypeFact; }
Fact* voltage () { return &_voltageFact; }
Fact* percentRemaining () { return &_percentRemainingFact; }
Fact* mahConsumed () { return &_mahConsumedFact; }
Fact* current () { return &_currentFact; }
Fact* temperature () { return &_temperatureFact; }
Fact* instantPower () { return &_instantPowerFact; }
Fact* timeRemaining () { return &_timeRemainingFact; }
Fact* timeRemainingStr () { return &_timeRemainingStrFact; }
Fact* chargeState () { return &_chargeStateFact; }
static const char* _batteryIdFactName;
static const char* _batteryFunctionFactName;
static const char* _batteryTypeFactName;
static const char* _temperatureFactName;
static const char* _voltageFactName;
static const char* _currentFactName;
static const char* _mahConsumedFactName;
static const char* _percentRemainingFactName;
static const char* _timeRemainingFactName;
static const char* _timeRemainingStrFactName;
static const char* _chargeStateFactName;
static const char* _instantPowerFactName;
static const char* _settingsGroup;
/// Creates a new fact group for the battery id as needed and updates the Vehicle with it
static void handleMessageForFactGroupCreation(Vehicle* vehicle, mavlink_message_t& message);
// Overrides from FactGroup
void handleMessage(Vehicle* vehicle, mavlink_message_t& message) override;
private slots:
void _timeRemainingChanged(QVariant value);
private:
static void _handleHighLatency (Vehicle* vehicle, mavlink_message_t& message);
static void _handleHighLatency2 (Vehicle* vehicle, mavlink_message_t& message);
static void _handleBatteryStatus (Vehicle* vehicle, mavlink_message_t& message);
static VehicleBatteryFactGroup* _findOrAddBatteryGroupById (Vehicle* vehicle, uint8_t batteryId);
Fact _batteryIdFact;
Fact _batteryFunctionFact;
Fact _batteryTypeFact;
Fact _voltageFact;
Fact _currentFact;
Fact _mahConsumedFact;
Fact _temperatureFact;
Fact _percentRemainingFact;
Fact _timeRemainingFact;
Fact _timeRemainingStrFact;
Fact _chargeStateFact;
Fact _instantPowerFact;
static const char* _batteryFactGroupNamePrefix;
};
...@@ -176,6 +176,7 @@ void MockLink::_run1HzTasks(void) ...@@ -176,6 +176,7 @@ void MockLink::_run1HzTasks(void)
_sendHighLatency2(); _sendHighLatency2();
} else { } else {
_sendVibration(); _sendVibration();
_sendBatteryStatus();
_sendSysStatus(); _sendSysStatus();
_sendADSBVehicles(); _sendADSBVehicles();
if (!qgcApp()->runningUnitTests()) { if (!qgcApp()->runningUnitTests()) {
...@@ -360,9 +361,6 @@ void MockLink::_sendHighLatency2(void) ...@@ -360,9 +361,6 @@ void MockLink::_sendHighLatency2(void)
void MockLink::_sendSysStatus(void) void MockLink::_sendSysStatus(void)
{ {
if(_batteryRemaining > 50) {
_batteryRemaining = static_cast<int8_t>(100 - (_runningTime.elapsed() / 1000));
}
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_sys_status_pack_chan( mavlink_msg_sys_status_pack_chan(
_vehicleSystemId, _vehicleSystemId,
...@@ -375,11 +373,87 @@ void MockLink::_sendSysStatus(void) ...@@ -375,11 +373,87 @@ void MockLink::_sendSysStatus(void)
250, // load 250, // load
4200 * 4, // voltage_battery 4200 * 4, // voltage_battery
8000, // current_battery 8000, // current_battery
_batteryRemaining, // battery_remaining _battery1PctRemaining, // battery_remaining
0,0,0,0,0,0); 0,0,0,0,0,0);
respondWithMavlinkMessage(msg); respondWithMavlinkMessage(msg);
} }
void MockLink::_sendBatteryStatus(void)
{
if(_battery1PctRemaining > 1) {
_battery1PctRemaining = static_cast<int8_t>(100 - (_runningTime.elapsed() / 1000));
_battery1TimeRemaining = static_cast<double>(_batteryMaxTimeRemaining) * (static_cast<double>(_battery1PctRemaining) / 100.0);
if (_battery1PctRemaining > 50) {
_battery1ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
} else if (_battery1PctRemaining > 30) {
_battery1ChargeState = MAV_BATTERY_CHARGE_STATE_LOW;
} else if (_battery1PctRemaining > 20) {
_battery1ChargeState = MAV_BATTERY_CHARGE_STATE_CRITICAL;
} else {
_battery1ChargeState = MAV_BATTERY_CHARGE_STATE_EMERGENCY;
}
}
if(_battery2PctRemaining > 1) {
_battery2PctRemaining = static_cast<int8_t>(100 - ((_runningTime.elapsed() / 1000) / 2));
_battery2TimeRemaining = static_cast<double>(_batteryMaxTimeRemaining) * (static_cast<double>(_battery2PctRemaining) / 100.0);
if (_battery2PctRemaining > 50) {
_battery2ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
} else if (_battery2PctRemaining > 30) {
_battery2ChargeState = MAV_BATTERY_CHARGE_STATE_LOW;
} else if (_battery2PctRemaining > 20) {
_battery2ChargeState = MAV_BATTERY_CHARGE_STATE_CRITICAL;
} else {
_battery2ChargeState = MAV_BATTERY_CHARGE_STATE_EMERGENCY;
}
}
mavlink_message_t msg;
uint16_t rgVoltages[10];
uint16_t rgVoltagesNone[10];
for (int i=0; i<10; i++) {
rgVoltages[i] = UINT16_MAX;
rgVoltagesNone[i] = UINT16_MAX;
}
rgVoltages[0] = rgVoltages[1] = rgVoltages[2] = 4200;
mavlink_msg_battery_status_pack_chan(
_vehicleSystemId,
_vehicleComponentId,
static_cast<uint8_t>(_mavlinkChannel),
&msg,
1, // battery id
MAV_BATTERY_FUNCTION_ALL,
MAV_BATTERY_TYPE_LIPO,
2100, // temp cdegC
rgVoltages,
600, // battery cA
100, // current consumed mAh
-1, // energy consumed not supported
_battery1PctRemaining,
_battery1TimeRemaining,
_battery1ChargeState);
respondWithMavlinkMessage(msg);
mavlink_msg_battery_status_pack_chan(
_vehicleSystemId,
_vehicleComponentId,
static_cast<uint8_t>(_mavlinkChannel),
&msg,
2, // battery id
MAV_BATTERY_FUNCTION_ALL,
MAV_BATTERY_TYPE_LIPO,
INT16_MAX, // temp cdegC
rgVoltagesNone,
600, // battery cA
100, // current consumed mAh
-1, // energy consumed not supported
_battery2PctRemaining,
_battery2TimeRemaining,
_battery2ChargeState);
respondWithMavlinkMessage(msg);
}
void MockLink::_sendVibration(void) void MockLink::_sendVibration(void)
{ {
mavlink_message_t msg; mavlink_message_t msg;
......
...@@ -224,6 +224,7 @@ private: ...@@ -224,6 +224,7 @@ private:
void _sendGpsRawInt (void); void _sendGpsRawInt (void);
void _sendVibration (void); void _sendVibration (void);
void _sendSysStatus (void); void _sendSysStatus (void);
void _sendBatteryStatus (void);
void _sendStatusTextMessages (void); void _sendStatusTextMessages (void);
void _sendChunkedStatusText (uint16_t chunkId, bool missingChunks); void _sendChunkedStatusText (uint16_t chunkId, bool missingChunks);
void _respondWithAutopilotVersion (void); void _respondWithAutopilotVersion (void);
...@@ -257,8 +258,14 @@ private: ...@@ -257,8 +258,14 @@ private:
uint32_t _mavCustomMode; uint32_t _mavCustomMode;
uint8_t _mavState; uint8_t _mavState;
QElapsedTimer _runningTime; QElapsedTimer _runningTime;
int8_t _batteryRemaining = 100; static const int32_t _batteryMaxTimeRemaining = 15 * 60;
int8_t _battery1PctRemaining = 100;
int32_t _battery1TimeRemaining = _batteryMaxTimeRemaining;
MAV_BATTERY_CHARGE_STATE _battery1ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
int8_t _battery2PctRemaining = 100;
int32_t _battery2TimeRemaining = _batteryMaxTimeRemaining;
MAV_BATTERY_CHARGE_STATE _battery2ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
MAV_AUTOPILOT _firmwareType; MAV_AUTOPILOT _firmwareType;
MAV_TYPE _vehicleType; MAV_TYPE _vehicleType;
......
...@@ -30,7 +30,6 @@ Rectangle { ...@@ -30,7 +30,6 @@ Rectangle {
anchors.fill: parent anchors.fill: parent
anchors.margins: ScreenTools.defaultFontPixelWidth anchors.margins: ScreenTools.defaultFontPixelWidth
property Fact _percentRemainingAnnounce: QGroundControl.settingsManager.appSettings.batteryPercentRemainingAnnounce
property Fact _savePath: QGroundControl.settingsManager.appSettings.savePath property Fact _savePath: QGroundControl.settingsManager.appSettings.savePath
property Fact _appFontPointSize: QGroundControl.settingsManager.appSettings.appFontPointSize property Fact _appFontPointSize: QGroundControl.settingsManager.appSettings.appFontPointSize
property Fact _userBrandImageIndoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageIndoor property Fact _userBrandImageIndoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageIndoor
...@@ -623,28 +622,6 @@ Rectangle { ...@@ -623,28 +622,6 @@ Rectangle {
} }
} }
} }
RowLayout {
visible: QGroundControl.settingsManager.appSettings.batteryPercentRemainingAnnounce.visible
QGCCheckBox {
id: announcePercentCheckbox
text: qsTr("Announce battery lower than")
checked: _percentRemainingAnnounce.value !== 0
onClicked: {
if (checked) {
_percentRemainingAnnounce.value = _percentRemainingAnnounce.defaultValueString
} else {
_percentRemainingAnnounce.value = 0
}
}
}
FactTextField {
fact: _percentRemainingAnnounce
Layout.preferredWidth: _valueFieldWidth
enabled: announcePercentCheckbox.checked
}
}
} }
} }
......
This diff is collapsed.
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