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)
}
}
This diff is collapsed.
......@@ -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