Unverified Commit 6bd75d16 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6474 from DonLakeFlyer/Battery2Work

Battery2 work: Support in FactGroups and ArduPilot Power page
parents 3a681376 0a7a9ff0
......@@ -83,10 +83,9 @@ SetupPage {
id: newFramePageComponent
Grid {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margins
columns: 2
width: availableWidth
spacing: _margins
columns: 2
QGCLabel {
text: qsTr("Frame Class:")
......
......@@ -23,22 +23,64 @@ SetupPage {
id: powerPage
pageComponent: powerPageComponent
FactPanelController {
id: controller
factPanel: powerPage.viewPanel
}
Component {
id: powerPageComponent
Column {
spacing: _margins
property Fact armVoltMin: controller.getParameterFact(-1, "r.ARMING_VOLT_MIN")
property Fact battAmpPerVolt: controller.getParameterFact(-1, "BATT_AMP_PERVOLT")
property Fact battCapacity: controller.getParameterFact(-1, "BATT_CAPACITY")
property Fact battCurrPin: controller.getParameterFact(-1, "BATT_CURR_PIN")
property Fact battMonitor: controller.getParameterFact(-1, "BATT_MONITOR")
property Fact battVoltMult: controller.getParameterFact(-1, "BATT_VOLT_MULT")
property Fact battVoltPin: controller.getParameterFact(-1, "BATT_VOLT_PIN")
QGCLabel { text: qsTr("Battery 1"); font.pointSize: ScreenTools.mediumFontPointSize }
Loader {
sourceComponent: powerSetupComponent
property Fact armVoltMin: controller.getParameterFact(-1, "r.ARMING_VOLT_MIN")
property Fact battAmpPerVolt: controller.getParameterFact(-1, "BATT_AMP_PERVOLT")
property Fact battCapacity: controller.getParameterFact(-1, "BATT_CAPACITY")
property Fact battCurrPin: controller.getParameterFact(-1, "BATT_CURR_PIN")
property Fact battMonitor: controller.getParameterFact(-1, "BATT_MONITOR")
property Fact battVoltMult: controller.getParameterFact(-1, "BATT_VOLT_MULT")
property Fact battVoltPin: controller.getParameterFact(-1, "BATT_VOLT_PIN")
property Fact vehicleVoltage: controller.vehicle.battery.voltage
property Fact vehicleCurrent: controller.vehicle.battery.current
}
Item {
height: ScreenTools.defaultFontPixelHeight
width: 1
}
QGCLabel { text: qsTr("Battery 2"); font.pointSize: ScreenTools.mediumFontPointSize }
Loader {
sourceComponent: powerSetupComponent
property Fact armVoltMin: controller.getParameterFact(-1, "r.ARMING_VOLT2_MIN")
property Fact battAmpPerVolt: controller.getParameterFact(-1, "BATT2_AMP_PERVOL")
property Fact battCapacity: controller.getParameterFact(-1, "BATT2_CAPACITY")
property Fact battCurrPin: controller.getParameterFact(-1, "BATT2_CURR_PIN")
property Fact battMonitor: controller.getParameterFact(-1, "BATT2_MONITOR")
property Fact battVoltMult: controller.getParameterFact(-1, "BATT2_VOLT_MULT")
property Fact battVoltPin: controller.getParameterFact(-1, "BATT2_VOLT_PIN")
property Fact vehicleVoltage: controller.vehicle.battery2.voltage
property Fact vehicleCurrent: controller.vehicle.battery2.current
}
}
} // Component - powerPageComponent
Component {
id: powerSetupComponent
Column {
spacing: _margins
property real _margins: ScreenTools.defaultFontPixelHeight / 2
property bool _showAdvanced: sensorCombo.currentIndex == sensorModel.count - 1
property bool _showAdvanced: sensorCombo.currentIndex === sensorModel.count - 1
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 25
Component.onCompleted: calcSensor()
......@@ -58,11 +100,6 @@ SetupPage {
QGCPalette { id: palette; colorGroupEnabled: true }
FactPanelController {
id: controller
factPanel: powerPage.viewPanel
}
ListModel {
id: sensorModel
......@@ -95,121 +132,6 @@ SetupPage {
}
}
Component {
id: calcVoltageMultiplierDlgComponent
QGCViewDialog {
id: calcVoltageMultiplierDlg
QGCFlickable {
anchors.fill: parent
contentHeight: column.height
contentWidth: column.width
Column {
id: column
width: calcVoltageMultiplierDlg.width
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new voltage multiplier.")
}
Grid {
columns: 2
spacing: ScreenTools.defaultFontPixelHeight / 2
verticalItemAlignment: Grid.AlignVCenter
QGCLabel {
text: qsTr("Measured voltage:")
}
QGCTextField { id: measuredVoltage }
QGCLabel { text: qsTr("Vehicle voltage:") }
QGCLabel { text: controller.vehicle.battery.voltage.valueString }
QGCLabel { text: qsTr("Voltage multiplier:") }
FactLabel { fact: battVoltMult }
}
QGCButton {
text: "Calculate"
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
if (measuredVoltageValue == 0 || isNaN(measuredVoltageValue)) {
return
}
var newVoltageMultiplier = (measuredVoltageValue * battVoltMult.value) / controller.vehicle.battery.voltage.value
if (newVoltageMultiplier > 0) {
battVoltMult.value = newVoltageMultiplier
}
}
}
} // Column
} // QGCFlickable
} // QGCViewDialog
} // Component - calcVoltageMultiplierDlgComponent
Component {
id: calcAmpsPerVoltDlgComponent
QGCViewDialog {
id: calcAmpsPerVoltDlg
QGCFlickable {
anchors.fill: parent
contentHeight: column.height
contentWidth: column.width
Column {
id: column
width: calcAmpsPerVoltDlg.width
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Measure current draw using an external current meter and enter the value below. Click Calculate to set the new amps per volt value.")
}
Grid {
columns: 2
spacing: ScreenTools.defaultFontPixelHeight / 2
verticalItemAlignment: Grid.AlignVCenter
QGCLabel {
text: qsTr("Measured current:")
}
QGCTextField { id: measuredCurrent }
QGCLabel { text: qsTr("Vehicle current:") }
QGCLabel { text: controller.vehicle.battery.current.valueString }
QGCLabel { text: qsTr("Amps per volt:") }
FactLabel { fact: battAmpPerVolt }
}
QGCButton {
text: "Calculate"
onClicked: {
var measuredCurrentValue = parseFloat(measuredCurrent.text)
if (measuredCurrentValue == 0) {
return
}
var newAmpsPerVolt = (measuredCurrentValue * battAmpPerVolt.value) / controller.vehicle.battery.current.value
if (newAmpsPerVolt != 0) {
battAmpPerVolt.value = newAmpsPerVolt
}
}
}
} // Column
} // QGCFlickable
} // QGCViewDialog
} // Component - calcAmpsPerVoltDlgComponent
GridLayout {
columns: 3
......@@ -351,9 +273,125 @@ SetupPage {
font.pointSize: ScreenTools.smallFontPointSize
wrapMode: Text.WordWrap
text: qsTr("If the current draw reported by the vehicle is largely different than the current read externally using a current meter you can adjust the amps per volt value to correct this. Click the Calculate button for help with calculating a new value.")
visible: _showAdvanced
visible: _showAdvanced
}
} // GridLayout
} // Column
} // Component
} // Component - powerSetupComponent
Component {
id: calcVoltageMultiplierDlgComponent
QGCViewDialog {
id: calcVoltageMultiplierDlg
QGCFlickable {
anchors.fill: parent
contentHeight: column.height
contentWidth: column.width
Column {
id: column
width: calcVoltageMultiplierDlg.width
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new voltage multiplier.")
}
Grid {
columns: 2
spacing: ScreenTools.defaultFontPixelHeight / 2
verticalItemAlignment: Grid.AlignVCenter
QGCLabel {
text: qsTr("Measured voltage:")
}
QGCTextField { id: measuredVoltage }
QGCLabel { text: qsTr("Vehicle voltage:") }
QGCLabel { text: vehicleVoltage.valueString }
QGCLabel { text: qsTr("Voltage multiplier:") }
FactLabel { fact: battVoltMult }
}
QGCButton {
text: "Calculate"
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
if (measuredVoltageValue == 0 || isNaN(measuredVoltageValue)) {
return
}
var newVoltageMultiplier = (measuredVoltageValue * battVoltMult.value) / vehicleVoltage.value
if (newVoltageMultiplier > 0) {
battVoltMult.value = newVoltageMultiplier
}
}
}
} // Column
} // QGCFlickable
} // QGCViewDialog
} // Component - calcVoltageMultiplierDlgComponent
Component {
id: calcAmpsPerVoltDlgComponent
QGCViewDialog {
id: calcAmpsPerVoltDlg
QGCFlickable {
anchors.fill: parent
contentHeight: column.height
contentWidth: column.width
Column {
id: column
width: calcAmpsPerVoltDlg.width
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Measure current draw using an external current meter and enter the value below. Click Calculate to set the new amps per volt value.")
}
Grid {
columns: 2
spacing: ScreenTools.defaultFontPixelHeight / 2
verticalItemAlignment: Grid.AlignVCenter
QGCLabel {
text: qsTr("Measured current:")
}
QGCTextField { id: measuredCurrent }
QGCLabel { text: qsTr("Vehicle current:") }
QGCLabel { text: vehicleCurrent.valueString }
QGCLabel { text: qsTr("Amps per volt:") }
FactLabel { fact: battAmpPerVolt }
}
QGCButton {
text: "Calculate"
onClicked: {
var measuredCurrentValue = parseFloat(measuredCurrent.text)
if (measuredCurrentValue == 0) {
return
}
var newAmpsPerVolt = (measuredCurrentValue * battAmpPerVolt.value) / vehicleCurrent.value
if (newAmpsPerVolt != 0) {
battAmpPerVolt.value = newAmpsPerVolt
}
}
}
} // Column
} // QGCFlickable
} // QGCViewDialog
} // Component - calcAmpsPerVoltDlgComponent
} // SetupPage
......@@ -69,7 +69,8 @@ const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_hobbsFactName = "hobbs";
const char* Vehicle::_gpsFactGroupName = "gps";
const char* Vehicle::_batteryFactGroupName = "battery";
const char* Vehicle::_battery1FactGroupName = "battery";
const char* Vehicle::_battery2FactGroupName = "battery2";
const char* Vehicle::_windFactGroupName = "wind";
const char* Vehicle::_vibrationFactGroupName = "vibration";
const char* Vehicle::_temperatureFactGroupName = "temperature";
......@@ -185,7 +186,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this)
, _batteryFactGroup(this)
, _battery1FactGroup(this)
, _battery2FactGroup(this)
, _windFactGroup(this)
, _vibrationFactGroup(this)
, _temperatureFactGroup(this)
......@@ -370,7 +372,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this)
, _batteryFactGroup(this)
, _battery1FactGroup(this)
, _battery2FactGroup(this)
, _windFactGroup(this)
, _vibrationFactGroup(this)
, _clockFactGroup(this)
......@@ -440,7 +443,8 @@ void Vehicle::_commonInit(void)
_addFact(&_hobbsFact, _hobbsFactName);
_addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
_addFactGroup(&_batteryFactGroup, _batteryFactGroupName);
_addFactGroup(&_battery1FactGroup, _battery1FactGroupName);
_addFactGroup(&_battery2FactGroup, _battery2FactGroupName);
_addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName);
......@@ -940,7 +944,7 @@ void Vehicle::_handleHighLatency2(mavlink_message_t& message)
_windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0);
_windFactGroup.speed()->setRawValue((double)highLatency2.windspeed / 5.0);
_batteryFactGroup.percentRemaining()->setRawValue(highLatency2.battery);
_battery1FactGroup.percentRemaining()->setRawValue(highLatency2.battery);
_temperatureFactGroup.temperature1()->setRawValue(highLatency2.temperature_air);
......@@ -1245,19 +1249,19 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
mavlink_msg_sys_status_decode(&message, &sysStatus);
if (sysStatus.current_battery == -1) {
_batteryFactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
_battery1FactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
} else {
// Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
_batteryFactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
_battery1FactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
}
if (sysStatus.voltage_battery == UINT16_MAX) {
_batteryFactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
_battery1FactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
} else {
_batteryFactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
_battery1FactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
// current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
_batteryFactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
_battery1FactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
}
_batteryFactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
_battery1FactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
if (sysStatus.battery_remaining > 0) {
if (sysStatus.battery_remaining < _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt() &&
......@@ -1300,15 +1304,17 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
mavlink_battery_status_t bat_status;
mavlink_msg_battery_status_decode(&message, &bat_status);
VehicleBatteryFactGroup& batteryFactGroup = bat_status.id == 0 ? _battery1FactGroup : _battery2FactGroup;
if (bat_status.temperature == INT16_MAX) {
_batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
} else {
_batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
}
if (bat_status.current_consumed == -1) {
_batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
} else {
_batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
}
int cellCount = 0;
......@@ -1321,15 +1327,15 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
cellCount = -1;
}
_batteryFactGroup.cellCount()->setRawValue(cellCount);
batteryFactGroup.cellCount()->setRawValue(cellCount);
//-- Time remaining in seconds (0 means not supported)
_batteryFactGroup.timeRemaining()->setRawValue(bat_status.time_remaining);
batteryFactGroup.timeRemaining()->setRawValue(bat_status.time_remaining);
//-- Battery charge state (0 means not supported)
if(bat_status.charge_state <= MAV_BATTERY_CHARGE_STATE_UNHEALTHY) {
_batteryFactGroup.chargeState()->setRawValue(bat_status.charge_state);
batteryFactGroup.chargeState()->setRawValue(bat_status.charge_state);
} else {
_batteryFactGroup.chargeState()->setRawValue(0);
batteryFactGroup.chargeState()->setRawValue(0);
}
//-- TODO: Somewhere, actions would be taken based on this chargeState:
// MAV_BATTERY_CHARGE_STATE_CRITICAL: Battery state is critical, return / abort immediately
......
......@@ -526,7 +526,8 @@ public:
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery READ batteryFactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery READ battery1FactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery2 READ battery2FactGroup CONSTANT)
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
......@@ -816,7 +817,8 @@ public:
Fact* hobbs (void) { return &_hobbsFact; }
FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
FactGroup* batteryFactGroup (void) { return &_batteryFactGroup; }
FactGroup* battery1FactGroup (void) { return &_battery1FactGroup; }
FactGroup* battery2FactGroup (void) { return &_battery2FactGroup; }
FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
......@@ -1294,7 +1296,8 @@ private:
Fact _hobbsFact;
VehicleGPSFactGroup _gpsFactGroup;
VehicleBatteryFactGroup _batteryFactGroup;
VehicleBatteryFactGroup _battery1FactGroup;
VehicleBatteryFactGroup _battery2FactGroup;
VehicleWindFactGroup _windFactGroup;
VehicleVibrationFactGroup _vibrationFactGroup;
VehicleTemperatureFactGroup _temperatureFactGroup;
......@@ -1319,7 +1322,8 @@ private:
static const char* _hobbsFactName;
static const char* _gpsFactGroupName;
static const char* _batteryFactGroupName;
static const char* _battery1FactGroupName;
static const char* _battery2FactGroupName;
static const char* _windFactGroupName;
static const char* _vibrationFactGroupName;
static const char* _temperatureFactGroupName;
......
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