mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: added a "battery" backend for liquid fuel flow
This is for sensors that give a pulse for each fixed volume of fuel. Output is: - current in Amps maps to in litres/hour - consumed mAh is in consumed millilitres - fixed 1.0v voltage
This commit is contained in:
parent
6bf600c587
commit
5571a84a49
|
@ -4,6 +4,7 @@
|
|||
#include "AP_BattMonitor_Bebop.h"
|
||||
#include "AP_BattMonitor_BLHeliESC.h"
|
||||
#include "AP_BattMonitor_Sum.h"
|
||||
#include "AP_BattMonitor_FuelFlow.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
|
@ -138,6 +139,9 @@ AP_BattMonitor::init()
|
|||
case AP_BattMonitor_Params::BattMonitor_TYPE_Sum:
|
||||
drivers[instance] = new AP_BattMonitor_Sum(*this, state[instance], _params[instance], instance);
|
||||
break;
|
||||
case AP_BattMonitor_Params::BattMonitor_TYPE_FuelFlow:
|
||||
drivers[instance] = new AP_BattMonitor_FuelFlow(*this, state[instance], _params[instance]);
|
||||
break;
|
||||
case AP_BattMonitor_Params::BattMonitor_TYPE_NONE:
|
||||
default:
|
||||
break;
|
||||
|
|
|
@ -36,6 +36,7 @@ class AP_BattMonitor
|
|||
friend class AP_BattMonitor_SMBus_Maxell;
|
||||
friend class AP_BattMonitor_UAVCAN;
|
||||
friend class AP_BattMonitor_Sum;
|
||||
friend class AP_BattMonitor_FuelFlow;
|
||||
|
||||
public:
|
||||
|
||||
|
|
|
@ -0,0 +1,124 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_BattMonitor_FuelFlow.h"
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
/*
|
||||
"battery" monitor for liquid fuel flow systems that give a pulse on
|
||||
a pin for fixed volumes of fuel.
|
||||
|
||||
this driver assumes that BATTx_AMP_PERVLT is set to give the
|
||||
number of millilitres per pulse.
|
||||
|
||||
Output is:
|
||||
|
||||
- current in Amps maps to in litres/hour
|
||||
- consumed mAh is in consumed millilitres
|
||||
- fixed 1.0v voltage
|
||||
*/
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define FUELFLOW_MIN_PULSE_DELTA_US 10
|
||||
|
||||
/// Constructor
|
||||
AP_BattMonitor_FuelFlow::AP_BattMonitor_FuelFlow(AP_BattMonitor &mon,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_BattMonitor_Params ¶ms) :
|
||||
AP_BattMonitor_Backend(mon, mon_state, params)
|
||||
{
|
||||
_state.voltage = 1.0; // show a fixed voltage of 1v
|
||||
|
||||
// we can't tell if it is healthy as we expect zero pulses when no
|
||||
// fuel is flowing
|
||||
_state.healthy = true;
|
||||
}
|
||||
|
||||
/*
|
||||
handle interrupt on an instance
|
||||
*/
|
||||
void AP_BattMonitor_FuelFlow::irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp)
|
||||
{
|
||||
if (irq_state.last_pulse_us == 0) {
|
||||
irq_state.last_pulse_us = timestamp;
|
||||
return;
|
||||
}
|
||||
uint32_t delta = timestamp - irq_state.last_pulse_us;
|
||||
if (delta < FUELFLOW_MIN_PULSE_DELTA_US) {
|
||||
// simple de-bounce
|
||||
return;
|
||||
}
|
||||
irq_state.pulse_count++;
|
||||
irq_state.total_us += delta;
|
||||
irq_state.last_pulse_us = timestamp;
|
||||
}
|
||||
|
||||
/*
|
||||
read - read the "voltage" and "current"
|
||||
*/
|
||||
void AP_BattMonitor_FuelFlow::read()
|
||||
{
|
||||
int8_t pin = _params._curr_pin;
|
||||
if (last_pin != pin) {
|
||||
// detach from last pin
|
||||
if (last_pin != -1) {
|
||||
hal.gpio->detach_interrupt(last_pin);
|
||||
}
|
||||
// attach to new pin
|
||||
last_pin = pin;
|
||||
if (last_pin > 0) {
|
||||
hal.gpio->pinMode(last_pin, HAL_GPIO_INPUT);
|
||||
if (!hal.gpio->attach_interrupt(
|
||||
last_pin,
|
||||
FUNCTOR_BIND_MEMBER(&AP_BattMonitor_FuelFlow::irq_handler, void, uint8_t, bool, uint32_t),
|
||||
AP_HAL::GPIO::INTERRUPT_RISING)) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "FuelFlow: Failed to attach to pin %u", last_pin);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t now_us = AP_HAL::micros();
|
||||
if (_state.last_time_micros == 0) {
|
||||
// need initial time, so we can work out expected pulse rate
|
||||
_state.last_time_micros = now_us;
|
||||
return;
|
||||
}
|
||||
float dt = (now_us - _state.last_time_micros) * 1.0e-6;
|
||||
|
||||
if (dt < 1 && irq_state.pulse_count == 0) {
|
||||
// we allow for up to 1 second with no pulses to cope with low
|
||||
// flow idling. After that we will start reading zero current
|
||||
return;
|
||||
}
|
||||
|
||||
// get the IRQ state with interrupts disabled
|
||||
struct IrqState state;
|
||||
void *irqstate = hal.scheduler->disable_interrupts_save();
|
||||
state = irq_state;
|
||||
irq_state.pulse_count = 0;
|
||||
irq_state.total_us = 0;
|
||||
hal.scheduler->restore_interrupts(irqstate);
|
||||
|
||||
/*
|
||||
this driver assumes that BATTx_AMP_PERVLT is set to give the
|
||||
number of millilitres per pulse.
|
||||
*/
|
||||
float irq_dt = state.total_us * 1.0e-6;
|
||||
float litres, litres_pec_sec;
|
||||
if (state.pulse_count == 0) {
|
||||
litres = 0;
|
||||
litres_pec_sec = 0;
|
||||
} else {
|
||||
litres = state.pulse_count * _params._curr_amp_per_volt * 0.001;
|
||||
litres_pec_sec = litres / irq_dt;
|
||||
}
|
||||
|
||||
_state.last_time_micros = now_us;
|
||||
|
||||
// map amps to litres/hour
|
||||
_state.current_amps = litres_pec_sec * (60*60);
|
||||
|
||||
// map consumed_mah to consumed millilitres
|
||||
_state.consumed_mah += litres * 1000;
|
||||
|
||||
// map consumed_wh using fixed voltage of 1
|
||||
_state.consumed_wh = _state.consumed_mah;
|
||||
}
|
|
@ -0,0 +1,34 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_BattMonitor.h"
|
||||
#include "AP_BattMonitor_Backend.h"
|
||||
|
||||
class AP_BattMonitor_FuelFlow : public AP_BattMonitor_Backend
|
||||
{
|
||||
public:
|
||||
|
||||
/// Constructor
|
||||
AP_BattMonitor_FuelFlow(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms);
|
||||
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void read() override;
|
||||
|
||||
/// returns true if battery monitor provides consumed energy info
|
||||
bool has_consumed_energy() const override { return true; }
|
||||
|
||||
/// returns true if battery monitor provides current info
|
||||
bool has_current() const override { return true; }
|
||||
|
||||
void init(void) override {}
|
||||
|
||||
private:
|
||||
void irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp);
|
||||
|
||||
struct IrqState {
|
||||
uint32_t pulse_count;
|
||||
uint32_t total_us;
|
||||
uint32_t last_pulse_us;
|
||||
} irq_state;
|
||||
|
||||
int8_t last_pin = -1;
|
||||
};
|
|
@ -13,7 +13,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
|
|||
// @Param: MONITOR
|
||||
// @DisplayName: Battery monitoring
|
||||
// @Description: Controls enabling monitoring of the battery's voltage and current
|
||||
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Maxell,8:UAVCAN-BatteryInfo,9:BLHeli ESC,10:SumOfFollowing
|
||||
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Maxell,8:UAVCAN-BatteryInfo,9:BLHeli ESC,10:SumOfFollowing,11:FuelFlow
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, BattMonitor_TYPE_NONE, AP_PARAM_FLAG_ENABLE),
|
||||
|
|
|
@ -23,6 +23,7 @@ public:
|
|||
BattMonitor_TYPE_UAVCAN_BatteryInfo = 8,
|
||||
BattMonitor_TYPE_BLHeliESC = 9,
|
||||
BattMonitor_TYPE_Sum = 10,
|
||||
BattMonitor_TYPE_FuelFlow = 11,
|
||||
};
|
||||
|
||||
// low voltage sources (used for BATT_LOW_TYPE parameter)
|
||||
|
|
Loading…
Reference in New Issue