Commit a5f2ab07 authored by dogmaphobic's avatar dogmaphobic

Adding Battery Consumption to the tool bar.

parent d0512114
...@@ -57,6 +57,7 @@ MavManager::MavManager(QObject *parent) ...@@ -57,6 +57,7 @@ MavManager::MavManager(QObject *parent)
, _refreshTimer(new QTimer(this)) , _refreshTimer(new QTimer(this))
, _batteryVoltage(0.0) , _batteryVoltage(0.0)
, _batteryPercent(0.0) , _batteryPercent(0.0)
, _batteryConsumed(0.0)
, _systemArmed(false) , _systemArmed(false)
, _currentHeartbeatTimeout(0) , _currentHeartbeatTimeout(0)
, _waypointDistance(0.0) , _waypointDistance(0.0)
...@@ -108,6 +109,7 @@ void MavManager::_forgetUAS(UASInterface* uas) ...@@ -108,6 +109,7 @@ void MavManager::_forgetUAS(UASInterface* uas)
disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData);
disconnect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); disconnect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout);
disconnect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); disconnect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining);
disconnect(_mav, &UASInterface::batteryConsumedChanged, this, &MavManager::_updateBatteryConsumedChanged);
disconnect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); disconnect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode);
disconnect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); disconnect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName);
disconnect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); disconnect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType);
...@@ -157,6 +159,7 @@ void MavManager::_setActiveUAS(UASInterface* uas) ...@@ -157,6 +159,7 @@ void MavManager::_setActiveUAS(UASInterface* uas)
connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData);
connect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); connect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout);
connect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); connect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining);
connect(_mav, &UASInterface::batteryConsumedChanged, this, &MavManager::_updateBatteryConsumedChanged);
connect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); connect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode);
connect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); connect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName);
connect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); connect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType);
...@@ -437,6 +440,15 @@ void MavManager::_updateBatteryRemaining(UASInterface*, double voltage, double, ...@@ -437,6 +440,15 @@ void MavManager::_updateBatteryRemaining(UASInterface*, double voltage, double,
} }
} }
void MavManager::_updateBatteryConsumedChanged(UASInterface*, double current_consumed)
{
if(_batteryConsumed != current_consumed) {
_batteryConsumed = current_consumed;
emit batteryConsumedChanged();
}
}
void MavManager::_updateState(UASInterface*, QString name, QString) void MavManager::_updateState(UASInterface*, QString name, QString)
{ {
if (_currentState != name) { if (_currentState != name) {
......
...@@ -76,6 +76,7 @@ public: ...@@ -76,6 +76,7 @@ public:
Q_PROPERTY(bool mavPresent READ mavPresent NOTIFY mavPresentChanged) Q_PROPERTY(bool mavPresent READ mavPresent NOTIFY mavPresentChanged)
Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged)
Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged)
Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged)
Q_PROPERTY(bool systemArmed READ systemArmed NOTIFY systemArmedChanged) Q_PROPERTY(bool systemArmed READ systemArmed NOTIFY systemArmedChanged)
Q_PROPERTY(QString currentMode READ currentMode NOTIFY currentModeChanged) Q_PROPERTY(QString currentMode READ currentMode NOTIFY currentModeChanged)
Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged) Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged)
...@@ -103,6 +104,7 @@ public: ...@@ -103,6 +104,7 @@ public:
int satelliteCount () { return _satelliteCount; } int satelliteCount () { return _satelliteCount; }
double batteryVoltage () { return _batteryVoltage; } double batteryVoltage () { return _batteryVoltage; }
double batteryPercent () { return _batteryPercent; } double batteryPercent () { return _batteryPercent; }
double batteryConsumed () { return _batteryConsumed; }
bool systemArmed () { return _systemArmed; } bool systemArmed () { return _systemArmed; }
QString currentMode () { return _currentMode; } QString currentMode () { return _currentMode; }
QString systemPixmap () { return _systemPixmap; } QString systemPixmap () { return _systemPixmap; }
...@@ -130,6 +132,7 @@ signals: ...@@ -130,6 +132,7 @@ signals:
void mavPresentChanged (); void mavPresentChanged ();
void batteryVoltageChanged (); void batteryVoltageChanged ();
void batteryPercentChanged (); void batteryPercentChanged ();
void batteryConsumedChanged ();
void systemArmedChanged (); void systemArmedChanged ();
void heartbeatTimeoutChanged(); void heartbeatTimeoutChanged();
void currentModeChanged (); void currentModeChanged ();
...@@ -158,6 +161,7 @@ private slots: ...@@ -158,6 +161,7 @@ private slots:
void _setActiveUAS (UASInterface* uas); void _setActiveUAS (UASInterface* uas);
void _checkUpdate (); void _checkUpdate ();
void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int);
void _updateBatteryConsumedChanged (UASInterface*, double current_consumed);
void _updateArmingState (bool armed); void _updateArmingState (bool armed);
void _updateState (UASInterface* system, QString name, QString description); void _updateState (UASInterface* system, QString name, QString description);
void _updateMode (int system, QString name, QString description); void _updateMode (int system, QString name, QString description);
...@@ -197,6 +201,7 @@ private: ...@@ -197,6 +201,7 @@ private:
QList<int> _changes; QList<int> _changes;
double _batteryVoltage; double _batteryVoltage;
double _batteryPercent; double _batteryPercent;
double _batteryConsumed;
bool _systemArmed; bool _systemArmed;
QString _currentState; QString _currentState;
QString _currentMode; QString _currentMode;
......
...@@ -559,6 +559,19 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -559,6 +559,19 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
mavlink_battery_status_t bat_status;
mavlink_msg_battery_status_decode(&message, &bat_status);
emit batteryConsumedChanged(this, (double)bat_status.current_consumed);
}
break;
case MAVLINK_MSG_ID_SYS_STATUS: case MAVLINK_MSG_ID_SYS_STATUS:
{ {
if (multiComponentSourceDetected && wrongComponent) if (multiComponentSourceDetected && wrongComponent)
......
...@@ -488,6 +488,7 @@ signals: ...@@ -488,6 +488,7 @@ signals:
* @param seconds estimated remaining flight time in seconds * @param seconds estimated remaining flight time in seconds
*/ */
void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds); void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
void batteryConsumedChanged(UASInterface* uas, double current_consumed);
void statusChanged(UASInterface* uas, QString status); void statusChanged(UASInterface* uas, QString status);
void actuatorChanged(UASInterface*, int actId, double value); void actuatorChanged(UASInterface*, int actId, double value);
void thrustChanged(UASInterface*, double thrust); void thrustChanged(UASInterface*, double thrust);
......
...@@ -526,15 +526,14 @@ Rectangle { ...@@ -526,15 +526,14 @@ Rectangle {
} }
Rectangle { Rectangle {
id: battery id: batteryStatus
width: getProportionalDimmension(60) width: MavManager.batteryConsumed < 0.0 ? getProportionalDimmension(60) : getProportionalDimmension(80)
height: cellHeight height: cellHeight
visible: showMavStatus() && (mainToolBar.showBattery) visible: showMavStatus() && (mainToolBar.showBattery)
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
color: getBatteryColor(); color: getBatteryColor();
border.color: "#00000000" border.color: "#00000000"
border.width: 0 border.width: 0
Image { Image {
source: getBatteryIcon(); source: getBatteryIcon();
height: getProportionalDimmension(20) height: getProportionalDimmension(20)
...@@ -547,16 +546,38 @@ Rectangle { ...@@ -547,16 +546,38 @@ Rectangle {
} }
QGCLabel { QGCLabel {
id: batteryText visible: batteryStatus.visible && MavManager.batteryConsumed < 0.0
text: MavManager.batteryVoltage.toFixed(1) + 'V'; text: MavManager.batteryVoltage.toFixed(1) + 'V';
font.pointSize: ScreenTools.fontPointFactor * (11); font.pointSize: ScreenTools.fontPointFactor * (11);
font.weight: Font.DemiBold font.weight: Font.DemiBold
anchors.verticalCenter: parent.verticalCenter
anchors.right: parent.right anchors.right: parent.right
anchors.rightMargin: getProportionalDimmension(6) anchors.rightMargin: getProportionalDimmension(6)
horizontalAlignment: Text.AlignRight horizontalAlignment: Text.AlignRight
color: colorWhite color: colorWhite
} }
Column {
anchors.verticalCenter: parent.verticalCenter
anchors.right: parent.right
anchors.rightMargin: getProportionalDimmension(6)
visible: batteryStatus.visible && MavManager.batteryConsumed >= 0.0
QGCLabel {
text: MavManager.batteryVoltage.toFixed(1) + 'V';
width: getProportionalDimmension(30)
horizontalAlignment: Text.AlignRight
font.pointSize: ScreenTools.fontPointFactor * (11);
font.weight: Font.DemiBold
color: colorWhite
}
QGCLabel {
text: MavManager.batteryConsumed.toFixed(0) + 'mA';
width: getProportionalDimmension(30)
horizontalAlignment: Text.AlignRight
font.pointSize: ScreenTools.fontPointFactor * (11);
font.weight: Font.DemiBold
color: colorWhite
}
}
} }
Column { Column {
......
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