Unverified Commit 2dc44666 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #9016 from DonLakeFlyer/MultiBatterySetup

PX4: Multi battery setup
parents 979e9922 9ca7bbe7
/****************************************************************************
*
* (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.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
// Exposes the set of battery parameters for new and old firmwares
// Older firmware: BAT_* naming
// Newer firmware: BAT#_* naming, with indices starting at 1
QtObject {
property var controller ///< FactPanelController
property int batteryIndex ///< 1-based battery index
property bool battVoltageDividerAvailable: controller.parameterExists(-1, "BAT#_V_DIV".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""))
property bool battAmpsPerVoltAvailable: controller.parameterExists(-1, "BAT#_A_PER_V".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""))
property Fact battNumCells: controller.getParameterFact(-1, "BAT#_N_CELLS".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""))
property Fact battHighVolt: controller.getParameterFact(-1, "BAT#_V_CHARGED".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""))
property Fact battLowVolt: controller.getParameterFact(-1, "BAT#_V_EMPTY".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""))
property Fact battVoltLoadDrop: controller.getParameterFact(-1, "BAT#_V_LOAD_DROP".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""))
property Fact battVoltageDivider: controller.getParameterFact(-1, "BAT#_V_DIV".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""), false)
property Fact battAmpsPerVolt: controller.getParameterFact(-1, "BAT#_A_PER_V".replace("#", _indexedBatteryParamsAvailable ? batteryIndex : ""), false)
property string _batNCellsIndexedParamName: "BAT#_N_CELLS"
property bool _indexedBatteryParamsAvailable: controller.parameterExists(-1, _batNCellsIndexedParamName.replace("#", 1))
property int _indexedBatteryParamCount: getIndexedBatteryParamCount()
Component.onCompleted: {
if (batteryIndex > 1 && !_indexedBatteryParamsAvailable) {
console.warn("Internal Error: BatteryParams.qml batteryIndex > 1 while indexed params are not available", batteryIndex)
}
}
function getIndexedBatteryParamCount() {
var batteryIndex = 1
do {
if (!controller.parameterExists(-1, _batNCellsIndexedParamName.replace("#", batteryIndex))) {
return batteryIndex - 1
}
batteryIndex++
} while (true)
}
}
......@@ -18,7 +18,11 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.PX4 1.0
// Note: This setup supports back compat on battery parameter naming
// Older firmware: Single battery setup using BAT_* naming
// Newer firmware: Multiple battery setup using BAT#_* naming, with indices starting at 1
SetupPage {
id: powerPage
pageComponent: pageComponent
......@@ -30,30 +34,34 @@ SetupPage {
width: Math.max(availableWidth, innerColumn.width)
height: innerColumn.height
property int textEditWidth: ScreenTools.defaultFontPixelWidth * 8
property Fact battNumCells: controller.getParameterFact(-1, "BAT_N_CELLS")
property Fact battHighVolt: controller.getParameterFact(-1, "BAT_V_CHARGED")
property Fact battLowVolt: controller.getParameterFact(-1, "BAT_V_EMPTY")
property Fact battVoltLoadDrop: controller.getParameterFact(-1, "BAT_V_LOAD_DROP")
property Fact battVoltageDivider: controller.getParameterFact(-1, "BAT_V_DIV")
property Fact battAmpsPerVolt: controller.getParameterFact(-1, "BAT_A_PER_V")
property Fact uavcanEnable: controller.getParameterFact(-1, "UAVCAN_ENABLE", false)
readonly property string highlightPrefix: "<font color=\"" + qgcPal.warningText + "\">"
readonly property string highlightSuffix: "</font>"
function getBatteryImage()
{
switch(battNumCells.value) {
case 1: return "/qmlimages/PowerComponentBattery_01cell.svg";
case 2: return "/qmlimages/PowerComponentBattery_02cell.svg"
case 3: return "/qmlimages/PowerComponentBattery_03cell.svg"
case 4: return "/qmlimages/PowerComponentBattery_04cell.svg"
case 5: return "/qmlimages/PowerComponentBattery_05cell.svg"
case 6: return "/qmlimages/PowerComponentBattery_06cell.svg"
default: return "/qmlimages/PowerComponentBattery_01cell.svg";
}
readonly property string _highlightPrefix: "<font color=\"" + qgcPal.warningText + "\">"
readonly property string _highlightSuffix: "</font>"
readonly property string _batNCellsIndexedParamName: "BAT#_N_CELLS"
property int _textEditWidth: ScreenTools.defaultFontPixelWidth * 8
property Fact _uavcanEnable: controller.getParameterFact(-1, "UAVCAN_ENABLE", false)
property bool _indexedBatteryParamsAvailable: controller.parameterExists(-1, _batNCellsIndexedParamName.replace("#", 1))
property int _indexedBatteryParamCount: getIndexedBatteryParamCount()
function getIndexedBatteryParamCount() {
var batteryIndex = 1
do {
if (!controller.parameterExists(-1, _batNCellsIndexedParamName.replace("#", batteryIndex))) {
return batteryIndex - 1
}
batteryIndex++
} while (true)
}
PowerComponentController {
id: controller
onOldFirmware: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("%1 cannot perform ESC Calibration with this version of firmware. You will need to upgrade to a newer firmware.").arg(QGroundControl.appName))
onNewerFirmware: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("%1 cannot perform ESC Calibration with this version of firmware. You will need to upgrade %1.").arg(QGroundControl.appName))
onBatteryConnected: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("Performing calibration. This will take a few seconds.."))
onCalibrationFailed: mainWindow.showMessageDialog(qsTr("ESC Calibration failed"), errorMessage)
onCalibrationSuccess: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("Calibration complete. You can disconnect your battery now if you like."))
onConnectBattery: mainWindow.showMessageDialog(qsTr("ESC Calibration"), _highlightPrefix + qsTr("WARNING: Props must be removed from vehicle prior to performing ESC calibration.") + _highlightSuffix + qsTr(" Connect the battery now and calibration will begin."))
onDisconnectBattery: mainWindow.showMessageDialog(qsTr("ESC Calibration failed"), qsTr("You must disconnect the battery prior to performing ESC Calibration. Disconnect your battery and try again."))
}
ColumnLayout {
......@@ -86,136 +94,159 @@ SetupPage {
drawArrowhead(ctx, x2, y2, rd);
}
PowerComponentController {
id: controller
onOldFirmware: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("%1 cannot perform ESC Calibration with this version of firmware. You will need to upgrade to a newer firmware.").arg(QGroundControl.appName))
onNewerFirmware: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("%1 cannot perform ESC Calibration with this version of firmware. You will need to upgrade %1.").arg(QGroundControl.appName))
onBatteryConnected: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("Performing calibration. This will take a few seconds.."))
onCalibrationFailed: mainWindow.showMessageDialog(qsTr("ESC Calibration failed"), errorMessage)
onCalibrationSuccess: mainWindow.showMessageDialog(qsTr("ESC Calibration"), qsTr("Calibration complete. You can disconnect your battery now if you like."))
onConnectBattery: mainWindow.showMessageDialog(qsTr("ESC Calibration"), highlightPrefix + qsTr("WARNING: Props must be removed from vehicle prior to performing ESC calibration.") + highlightSuffix + qsTr(" Connect the battery now and calibration will begin."))
onDisconnectBattery: mainWindow.showMessageDialog(qsTr("ESC Calibration failed"), qsTr("You must disconnect the battery prior to performing ESC Calibration. Disconnect your battery and try again."))
Repeater {
id: batterySetupRepeater
model: _indexedBatteryParamsAvailable ? _indexedBatteryParamCount : 1
Loader {
sourceComponent: batterySetupComponent
property int batteryIndex: index + 1
property bool showBatteryIndex: batterySetupRepeater.count > 1
property bool useIndexedParamNames: _indexedBatteryParamsAvailable
}
}
Component {
id: calcVoltageDividerDlgComponent
QGCViewDialog {
id: calcVoltageDividerDlg
QGCGroupBox {
Layout.fillWidth: true
title: qsTr("ESC PWM Minimum and Maximum Calibration")
QGCFlickable {
anchors.fill: parent
contentHeight: column.height
contentWidth: column.width
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth
Column {
id: column
width: calcVoltageDividerDlg.width
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
color: qgcPal.warningText
wrapMode: Text.WordWrap
text: qsTr("WARNING: Propellers must be removed from vehicle prior to performing ESC calibration.")
Layout.fillWidth: true
}
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.")
}
QGCLabel {
text: qsTr("You must use USB connection for this operation.")
}
Grid {
columns: 2
spacing: ScreenTools.defaultFontPixelHeight / 2
verticalItemAlignment: Grid.AlignVCenter
QGCButton {
text: qsTr("Calibrate")
width: ScreenTools.defaultFontPixelWidth * 20
onClicked: controller.calibrateEsc()
}
}
}
QGCLabel {
text: qsTr("Measured voltage:")
}
QGCTextField { id: measuredVoltage }
QGCCheckBox {
id: showUAVCAN
text: qsTr("Show UAVCAN Settings")
checked: _uavcanEnable ? _uavcanEnable.rawValue !== 0 : false
}
QGCLabel { text: qsTr("Vehicle voltage:") }
QGCLabel { text: controller.vehicle.battery.voltage.valueString }
QGCGroupBox {
Layout.fillWidth: true
title: qsTr("UAVCAN Bus Configuration")
visible: showUAVCAN.checked
QGCLabel { text: qsTr("Voltage divider:") }
FactLabel { fact: battVoltageDivider }
}
Row {
id: uavCanConfigRow
spacing: ScreenTools.defaultFontPixelWidth
QGCButton {
text: "Calculate"
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
if (measuredVoltageValue === 0 || isNaN(measuredVoltageValue)) {
return
}
var newVoltageDivider = (measuredVoltageValue * battVoltageDivider.value) / controller.vehicle.battery.voltage.value
if (newVoltageDivider > 0) {
battVoltageDivider.value = newVoltageDivider
}
}
}
} // Column
} // QGCFlickable
} // QGCViewDialog
} // Component - calcVoltageDividerDlgComponent
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.")
}
FactComboBox {
id: _uavcanEnabledCheckBox
width: ScreenTools.defaultFontPixelWidth * 20
fact: _uavcanEnable
indexModel: false
}
QGCLabel {
anchors.verticalCenter: parent.verticalCenter
text: qsTr("Change required restart")
}
}
}
QGCGroupBox {
Layout.fillWidth: true
title: qsTr("UAVCAN Motor Index and Direction Assignment")
visible: showUAVCAN.checked
Grid {
columns: 2
spacing: ScreenTools.defaultFontPixelHeight / 2
verticalItemAlignment: Grid.AlignVCenter
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
text: qsTr("Measured current:")
}
QGCTextField { id: measuredCurrent }
QGCLabel {
wrapMode: Text.WordWrap
color: qgcPal.warningText
text: qsTr("WARNING: Propellers must be removed from vehicle prior to performing UAVCAN ESC configuration.")
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Vehicle current:") }
QGCLabel { text: controller.vehicle.battery.current.valueString }
QGCLabel {
wrapMode: Text.WordWrap
text: qsTr("ESC parameters will only be accessible in the editor after assignment.")
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Amps per volt:") }
FactLabel { fact: battAmpsPerVolt }
}
QGCLabel {
wrapMode: Text.WordWrap
text: qsTr("Start the process, then turn each motor into its turn direction, in the order of their motor indices.")
Layout.fillWidth: true
}
QGCButton {
text: qsTr("Calculate")
onClicked: {
var measuredCurrentValue = parseFloat(measuredCurrent.text)
if (measuredCurrentValue === 0) {
return
}
var newAmpsPerVolt = (measuredCurrentValue * battAmpsPerVolt.value) / controller.vehicle.battery.current.value
if (newAmpsPerVolt != 0) {
battAmpsPerVolt.value = newAmpsPerVolt
}
}
}
} // Column
} // QGCFlickable
} // QGCViewDialog
} // Component - calcAmpsPerVoltDlgComponent
QGCButton {
text: qsTr("Start Assignment")
width: ScreenTools.defaultFontPixelWidth * 20
onClicked: controller.startBusConfigureActuators()
}
QGCButton {
text: qsTr("Stop Assignment")
width: ScreenTools.defaultFontPixelWidth * 20
onClicked: controller.stopBusConfigureActuators()
}
}
}
} // Column
Component {
id: batterySetupComponent
QGCGroupBox {
id: batteryGroup
title: qsTr("Battery")
title: qsTr("Battery ") + (showBatteryIndex ? batteryIndex : "")
property var _controller: controller
property int _batteryIndex: batteryIndex
BatteryParams {
id: batParams
controller: _controller
batteryIndex: _batteryIndex
}
property bool battVoltageDividerAvailable: batParams.battVoltageDividerAvailable
property bool battAmpsPerVoltAvailable: batParams.battAmpsPerVoltAvailable
property Fact battNumCells: batParams.battNumCells
property Fact battHighVolt: batParams.battHighVolt
property Fact battLowVolt: batParams.battLowVolt
property Fact battVoltLoadDrop: batParams.battVoltLoadDrop
property Fact battVoltageDivider: batParams.battVoltageDivider
property Fact battAmpsPerVolt: batParams.battAmpsPerVolt
function getBatteryImage() {
switch(battNumCells.value) {
case 1: return "/qmlimages/PowerComponentBattery_01cell.svg";
case 2: return "/qmlimages/PowerComponentBattery_02cell.svg"
case 3: return "/qmlimages/PowerComponentBattery_03cell.svg"
case 4: return "/qmlimages/PowerComponentBattery_04cell.svg"
case 5: return "/qmlimages/PowerComponentBattery_05cell.svg"
case 6: return "/qmlimages/PowerComponentBattery_06cell.svg"
default: return "/qmlimages/PowerComponentBattery_01cell.svg";
}
}
GridLayout {
id: batteryGrid
......@@ -223,18 +254,16 @@ SetupPage {
columnSpacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
text: qsTr("Number of Cells (in Series)")
text: qsTr("Number of Cells (in Series)")
}
FactTextField {
id: cellsField
width: textEditWidth
width: _textEditWidth
fact: battNumCells
showUnits: true
}
QGCColoredImage {
id: batteryImage
Layout.rowSpan: 3
width: height * 0.75
height: 100
......@@ -243,265 +272,256 @@ SetupPage {
smooth: true
color: qgcPal.text
cache: false
source: getBatteryImage();
source: getBatteryImage(batteryIndex)
}
Item { width: 1; height: 1; Layout.columnSpan: 2 }
QGCLabel {
id: battHighLabel
text: qsTr("Full Voltage (per cell)")
text: qsTr("Full Voltage (per cell)")
}
FactTextField {
id: battHighField
width: textEditWidth
width: _textEditWidth
fact: battHighVolt
showUnits: true
}
QGCLabel {
text: qsTr("Battery Max:")
text: qsTr("Battery Max:")
}
QGCLabel {
text: (battNumCells.value * battHighVolt.value).toFixed(1) + ' V'
text: (battNumCells.value * battHighVolt.value).toFixed(1) + ' V'
}
QGCLabel {
id: battLowLabel
text: qsTr("Empty Voltage (per cell)")
text: qsTr("Empty Voltage (per cell)")
}
FactTextField {
id: battLowField
width: textEditWidth
width: _textEditWidth
fact: battLowVolt
showUnits: true
}
QGCLabel {
text: qsTr("Battery Min:")
text: qsTr("Battery Min:")
}
QGCLabel {
text: (battNumCells.value * battLowVolt.value).toFixed(1) + ' V'
text: (battNumCells.value * battLowVolt.value).toFixed(1) + ' V'
}
QGCLabel {
text: qsTr("Voltage divider")
text: qsTr("Voltage divider")
visible: battVoltageDividerAvailable
}
FactTextField {
id: voltMultField
fact: battVoltageDivider
fact: battVoltageDivider
visible: battVoltageDividerAvailable
}
QGCButton {
id: voltMultCalculateButton
text: qsTr("Calculate")
onClicked: mainWindow.showComponentDialog(calcVoltageDividerDlgComponent, qsTr("Calculate Voltage Divider"), mainWindow.showDialogDefaultWidth, StandardButton.Close)
text: qsTr("Calculate")
visible: battVoltageDividerAvailable
onClicked: mainWindow.showPopupDialogFromComponent(calcVoltageDividerDlgComponent, { batteryIndex: _batteryIndex })
}
Item { width: 1; height: 1; Layout.columnSpan: 2 }
Item { width: 1; height: 1; Layout.columnSpan: 2; visible: battVoltageDividerAvailable }
QGCLabel {
id: voltMultHelp
Layout.columnSpan: batteryGrid.columns
Layout.fillWidth: true
font.pointSize: ScreenTools.smallFontPointSize
wrapMode: Text.WordWrap
text: qsTr("If the battery voltage reported by the vehicle is largely different than the voltage read externally using a voltmeter you can adjust the voltage multiplier value to correct this. ") +
qsTr("Click the Calculate button for help with calculating a new value.")
visible: battVoltageDividerAvailable
}
QGCLabel {
id: ampPerVoltLabel
text: qsTr("Amps per volt")
text: qsTr("Amps per volt")
visible: battAmpsPerVoltAvailable
}
FactTextField {
id: ampPerVoltField
fact: battAmpsPerVolt
fact: battAmpsPerVolt
visible: battAmpsPerVoltAvailable
}
QGCButton {
id: ampPerVoltCalculateButton
text: qsTr("Calculate")
onClicked: mainWindow.showComponentDialog(calcAmpsPerVoltDlgComponent, qsTr("Calculate Amps per Volt"), mainWindow.showDialogDefaultWidth, StandardButton.Close)
text: qsTr("Calculate")
visible: battAmpsPerVoltAvailable
onClicked: mainWindow.showPopupDialogFromComponent(calcAmpsPerVoltDlgComponent, { batteryIndex: _batteryIndex })
}
Item { width: 1; height: 1; Layout.columnSpan: 2 }
Item { width: 1; height: 1; Layout.columnSpan: 2; visible: battAmpsPerVoltAvailable }
QGCLabel {
id: ampPerVoltHelp
Layout.columnSpan: batteryGrid.columns
Layout.fillWidth: true
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. ") +
qsTr("Click the Calculate button for help with calculating a new value.")
visible: battAmpsPerVoltAvailable
}
} // Grid
} // QGCGroupBox - Battery settings
QGCGroupBox {
Layout.maximumWidth: batteryGroup.width
Layout.fillWidth: true
title: qsTr("ESC PWM Minimum and Maximum Calibration")
QGCCheckBox {
id: showAdvanced
Layout.columnSpan: batteryGrid.columns
text: qsTr("Show Advanced Settings")
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
text: qsTr("Voltage Drop on Full Load (per cell)")
visible: showAdvanced.checked
}
FactTextField {
id: battDropField
fact: battVoltLoadDrop
showUnits: true
visible: showAdvanced.checked
}
Item { width: 1; height: 1; Layout.columnSpan: 3; visible: showAdvanced.checked }
QGCLabel {
color: qgcPal.warningText
wrapMode: Text.WordWrap
text: qsTr("WARNING: Propellers must be removed from vehicle prior to performing ESC calibration.")
Layout.columnSpan: batteryGrid.columns
Layout.fillWidth: true
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Batteries show less voltage at high throttle. Enter the difference in Volts between idle throttle and full ") +
qsTr("throttle, divided by the number of battery cells. Leave at the default if unsure. ") +
_highlightPrefix + qsTr("If this value is set too high, the battery might be deep discharged and damaged.") + _highlightSuffix
visible: showAdvanced.checked
}
QGCLabel {
text: qsTr("You must use USB connection for this operation.")
text: qsTr("Compensated Minimum Voltage:")
visible: showAdvanced.checked
}
QGCButton {
text: qsTr("Calibrate")
width: ScreenTools.defaultFontPixelWidth * 20
onClicked: controller.calibrateEsc()
QGCLabel {
text: ((battNumCells.value * battLowVolt.value) - (battNumCells.value * battVoltLoadDrop.value)).toFixed(1) + qsTr(" V")
visible: showAdvanced.checked
}
}
}
QGCCheckBox {
id: showUAVCAN
text: qsTr("Show UAVCAN Settings")
checked: uavcanEnable ? uavcanEnable.rawValue !== 0 : false
}
Item { width: 1; height: 1; Layout.columnSpan: 3; visible: showAdvanced.checked }
} // Grid
} // QGCGroupBox - Battery settings
} // Component - batterySetupComponent
QGCGroupBox {
Layout.maximumWidth: batteryGroup.width
Layout.fillWidth: true
title: qsTr("UAVCAN Bus Configuration")
visible: showUAVCAN.checked
Component {
id: calcVoltageDividerDlgComponent
Row {
id: uavCanConfigRow
spacing: ScreenTools.defaultFontPixelWidth
QGCPopupDialog {
title: qsTr("Calculate Voltage Divider")
buttons: StandardButton.Close
FactComboBox {
id: uavcanEnabledCheckBox
width: ScreenTools.defaultFontPixelWidth * 20
fact: uavcanEnable
indexModel: false
}
property var _controller: controller
QGCLabel {
anchors.verticalCenter: parent.verticalCenter
text: qsTr("Change required restart")
}
BatteryParams {
id: batParams
controller: _controller
batteryIndex: dialogProperties.batteryIndex
}
}
QGCGroupBox {
Layout.maximumWidth: batteryGroup.width
Layout.fillWidth: true
title: qsTr("UAVCAN Motor Index and Direction Assignment")
visible: showUAVCAN.checked
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
wrapMode: Text.WordWrap
color: qgcPal.warningText
text: qsTr("WARNING: Propellers must be removed from vehicle prior to performing UAVCAN ESC configuration.")
Layout.fillWidth: true
Layout.preferredWidth: gridLayout.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.")
}
QGCLabel {
wrapMode: Text.WordWrap
text: qsTr("ESC parameters will only be accessible in the editor after assignment.")
Layout.fillWidth: true
}
GridLayout {
id: gridLayout
columns: 2
QGCLabel {
wrapMode: Text.WordWrap
text: qsTr("Start the process, then turn each motor into its turn direction, in the order of their motor indices.")
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Measured voltage:") }
QGCTextField { id: measuredVoltage }
QGCButton {
text: qsTr("Start Assignment")
width: ScreenTools.defaultFontPixelWidth * 20
onClicked: controller.busConfigureActuators()
QGCLabel { text: qsTr("Vehicle voltage:") }
QGCLabel { text: controller.vehicle.battery.voltage.valueString }
QGCLabel { text: qsTr("Voltage divider:") }
FactLabel { fact: batParams.battVoltageDivider }
}
QGCButton {
text: qsTr("Stop Assignment")
width: ScreenTools.defaultFontPixelWidth * 20
onClicked: controller.stopBusConfigureActuators()
}
}
}
text: qsTr("Calculate")
QGCCheckBox {
id: showAdvanced
text: qsTr("Show Advanced Settings")
}
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
if (measuredVoltageValue === 0 || isNaN(measuredVoltageValue)) {
return
}
var newVoltageDivider = (measuredVoltageValue * batParams.battVoltageDivider.value) / controller.vehicle.battery.voltage.value
if (newVoltageDivider > 0) {
batParams.battVoltageDivider.value = newVoltageDivider
}
}
}
} // Column
} // QGCViewDialog
} // Component - calcVoltageDividerDlgComponent
QGCGroupBox {
Layout.maximumWidth: batteryGroup.width
Layout.fillWidth: true
title: qsTr("Advanced Power Settings")
visible: showAdvanced.checked
Component {
id: calcAmpsPerVoltDlgComponent
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth
QGCPopupDialog {
title: qsTr("Calculate Amps per Volt")
buttons: StandardButton.Close
Row {
spacing: ScreenTools.defaultFontPixelWidth
property var _controller: controller
QGCLabel {
text: qsTr("Voltage Drop on Full Load (per cell)")
anchors.baseline: battDropField.baseline
}
BatteryParams {
id: batParams
controller: _controller
batteryIndex: dialogProperties.batteryIndex
}
FactTextField {
id: battDropField
width: textEditWidth
fact: battVoltLoadDrop
showUnits: true
}
}
ColumnLayout {
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
wrapMode: Text.WordWrap
text: qsTr("Batteries show less voltage at high throttle. Enter the difference in Volts between idle throttle and full ") +
qsTr("throttle, divided by the number of battery cells. Leave at the default if unsure. ") +
highlightPrefix + qsTr("If this value is set too high, the battery might be deep discharged and damaged.") + highlightSuffix
Layout.maximumWidth: ScreenTools.defaultFontPixelWidth * 60
Layout.preferredWidth: gridLayout.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.")
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
GridLayout {
id: gridLayout
columns: 2
QGCLabel {
text: qsTr("Compensated Minimum Voltage:")
}
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: batParams.battAmpsPerVolt }
}
QGCButton {
text: qsTr("Calculate")
QGCLabel {
text: ((battNumCells.value * battLowVolt.value) - (battNumCells.value * battVoltLoadDrop.value)).toFixed(1) + qsTr(" V")
onClicked: {
var measuredCurrentValue = parseFloat(measuredCurrent.text)
if (measuredCurrentValue === 0 || isNaN(measuredCurrentValue)) {
return
}
var newAmpsPerVolt = (measuredCurrentValue * batParams.battAmpsPerVolt.value) / controller.vehicle.battery.current.value
if (newAmpsPerVolt != 0) {
batParams.battAmpsPerVolt.value = newAmpsPerVolt
}
}
}
} // Column
} // QGCGroupBox - Advanced power settings
} // Column
}
}
}
} // Item
} // Component
} // SetupPage
......@@ -22,26 +22,26 @@ PowerComponentController::PowerComponentController(void)
void PowerComponentController::calibrateEsc(void)
{
_warningMessages.clear();
connect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
connect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleVehicleTextMessage);
_vehicle->startCalibration(Vehicle::CalibrationEsc);
}
void PowerComponentController::busConfigureActuators(void)
void PowerComponentController::startBusConfigureActuators(void)
{
_warningMessages.clear();
connect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
_uas->startBusConfig(UASInterface::StartBusConfigActuators);
connect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleVehicleTextMessage);
_vehicle->startUAVCANBusConfig();
}
void PowerComponentController::stopBusConfigureActuators(void)
{
disconnect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
_uas->startBusConfig(UASInterface::EndBusConfigActuators);
disconnect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleVehicleTextMessage);
_vehicle->stopUAVCANBusConfig();
}
void PowerComponentController::_stopCalibration(void)
{
disconnect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
disconnect(_vehicle, &Vehicle::textMessageReceived, this, &PowerComponentController::_handleVehicleTextMessage);
}
void PowerComponentController::_stopBusConfig(void)
......@@ -49,12 +49,9 @@ void PowerComponentController::_stopBusConfig(void)
_stopCalibration();
}
void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
void PowerComponentController::_handleVehicleTextMessage(int vehicleId, int /* compId */, int /* severity */, QString text)
{
Q_UNUSED(compId);
Q_UNUSED(severity);
if (uasId != _vehicle->id()) {
if (vehicleId != _vehicle->id()) {
return;
}
......
......@@ -29,7 +29,7 @@ public:
PowerComponentController(void);
Q_INVOKABLE void calibrateEsc(void);
Q_INVOKABLE void busConfigureActuators(void);
Q_INVOKABLE void startBusConfigureActuators(void);
Q_INVOKABLE void stopBusConfigureActuators(void);
signals:
......@@ -43,7 +43,7 @@ signals:
void calibrationSuccess(const QStringList& warningMessages);
private slots:
void _handleUASTextMessage(int uasId, int compId, int severity, QString text);
void _handleVehicleTextMessage(int vehicleId, int compId, int severity, QString text);
private:
void _stopCalibration(void);
......
......@@ -21,6 +21,7 @@
<file alias="SensorsComponentSummaryFixedWing.qml">../../AutoPilotPlugins/PX4/SensorsComponentSummaryFixedWing.qml</file>
<file alias="SensorsSetup.qml">../../AutoPilotPlugins/PX4/SensorsSetup.qml</file>
<file alias="QGroundControl/PX4/qmldir">../../QmlControls/QGroundControl/PX4/qmldir</file>
<file alias="QGroundControl/PX4/BatteryParams.qml">../../AutoPilotPlugins/PX4/BatteryParams.qml</file>
</qresource>
<qresource prefix="/json">
<file alias="PX4-MavCmdInfoCommon.json">PX4-MavCmdInfoCommon.json</file>
......
Module QGroundControl.PX4
BatteryParams 1.0 BatteryParams.qml
SensorSetupPage 1.0 SensorSetupPage.qml
......@@ -3665,6 +3665,22 @@ void Vehicle::stopCalibration(void)
0); // unused
}
void Vehicle::startUAVCANBusConfig(void)
{
sendMavCommand(defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
1); // start config
}
void Vehicle::stopUAVCANBusConfig(void)
{
sendMavCommand(defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
0); // stop config
}
void Vehicle::setSoloFirmware(bool soloFirmware)
{
if (soloFirmware != _soloFirmware) {
......
......@@ -1003,6 +1003,9 @@ public:
void startCalibration (CalibrationType calType);
void stopCalibration (void);
void startUAVCANBusConfig(void);
void stopUAVCANBusConfig(void);
Fact* roll () { return &_rollFact; }
Fact* pitch () { return &_pitchFact; }
Fact* heading () { return &_headingFact; }
......
......@@ -348,41 +348,6 @@ void UAS::receiveMessage(mavlink_message_t message)
#pragma warning(pop, 0)
#endif
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
if (!_vehicle) {
return;
}
int actuatorCal = 0;
switch (calType) {
case StartBusConfigActuators:
actuatorCal = 1;
break;
case EndBusConfigActuators:
actuatorCal = 0;
break;
}
_vehicle->sendMavCommand(_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
actuatorCal); // actuators
}
void UAS::stopBusConfig(void)
{
if (!_vehicle) {
return;
}
_vehicle->sendMavCommand(_vehicle->defaultComponentId(), // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
true, // showError
0); // cancel
}
/**
* Check if time is smaller than 40 years, assuming no system without Unix
* timestamp runs longer than 40 years continuously without reboot. In worst case
......
......@@ -180,9 +180,6 @@ public slots:
/** @brief Receive a message from one of the communication links. */
virtual void receiveMessage(mavlink_message_t message);
void startBusConfig(StartBusConfigType calType);
void stopBusConfig(void);
signals:
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
......
......@@ -39,17 +39,6 @@ public:
/** @brief The time interval the robot is switched on **/
virtual quint64 getUptime() const = 0;
enum StartBusConfigType {
StartBusConfigActuators,
EndBusConfigActuators,
};
/// Starts the specified bus configuration
virtual void startBusConfig(StartBusConfigType calType) = 0;
/// Ends any current bus configuration
virtual void stopBusConfig(void) = 0;
public slots:
/** @brief Order the robot to pair its receiver **/
virtual void pairRX(int rxType, int rxSubType) = 0;
......
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