Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_FUELFLOW_ENABLED34#include "AP_BattMonitor_FuelFlow.h"56#include <AP_HAL/AP_HAL.h>7#include <GCS_MAVLink/GCS.h>89/*10"battery" monitor for liquid fuel flow systems that give a pulse on11a pin for fixed volumes of fuel.1213this driver assumes that BATTx_AMP_PERVLT is set to give the14number of millilitres per pulse.1516Output is:1718- current in Amps maps to in litres/hour19- consumed mAh is in consumed millilitres20- fixed 1.0v voltage21*/22extern const AP_HAL::HAL& hal;2324#define FUELFLOW_MIN_PULSE_DELTA_US 102526/// Constructor27AP_BattMonitor_FuelFlow::AP_BattMonitor_FuelFlow(AP_BattMonitor &mon,28AP_BattMonitor::BattMonitor_State &mon_state,29AP_BattMonitor_Params ¶ms) :30AP_BattMonitor_Analog(mon, mon_state, params)31{32_state.voltage = 1.0; // show a fixed voltage of 1v3334// we can't tell if it is healthy as we expect zero pulses when no35// fuel is flowing36_state.healthy = true;37}3839/*40handle interrupt on an instance41*/42void AP_BattMonitor_FuelFlow::irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp)43{44if (irq_state.last_pulse_us == 0) {45irq_state.last_pulse_us = timestamp;46return;47}48uint32_t delta = timestamp - irq_state.last_pulse_us;49if (delta < FUELFLOW_MIN_PULSE_DELTA_US) {50// simple de-bounce51return;52}53irq_state.pulse_count++;54irq_state.total_us += delta;55irq_state.last_pulse_us = timestamp;56}5758/*59read - read the "voltage" and "current"60*/61void AP_BattMonitor_FuelFlow::read()62{63int8_t pin = _curr_pin;64if (last_pin != pin) {65// detach from last pin66if (last_pin != -1) {67hal.gpio->detach_interrupt(last_pin);68}69// attach to new pin70last_pin = pin;71if (last_pin > 0) {72hal.gpio->pinMode(last_pin, HAL_GPIO_INPUT);73if (!hal.gpio->attach_interrupt(74last_pin,75FUNCTOR_BIND_MEMBER(&AP_BattMonitor_FuelFlow::irq_handler, void, uint8_t, bool, uint32_t),76AP_HAL::GPIO::INTERRUPT_RISING)) {77GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "FuelFlow: Failed to attach to pin %u", last_pin);78}79}80}8182uint32_t now_us = AP_HAL::micros();83if (_state.last_time_micros == 0) {84// need initial time, so we can work out expected pulse rate85_state.last_time_micros = now_us;86return;87}88float dt = (now_us - _state.last_time_micros) * 1.0e-6f;8990if (dt < 1 && irq_state.pulse_count == 0) {91// we allow for up to 1 second with no pulses to cope with low92// flow idling. After that we will start reading zero current93return;94}9596// get the IRQ state with interrupts disabled97struct IrqState state;98void *irqstate = hal.scheduler->disable_interrupts_save();99state = irq_state;100irq_state.pulse_count = 0;101irq_state.total_us = 0;102hal.scheduler->restore_interrupts(irqstate);103104/*105this driver assumes that BATTx_AMP_PERVLT is set to give the106number of millilitres per pulse.107*/108float irq_dt = state.total_us * 1.0e-6f;109float litres, litres_pec_sec;110if (state.pulse_count == 0) {111litres = 0;112litres_pec_sec = 0;113} else {114litres = state.pulse_count * _curr_amp_per_volt * 0.001f;115litres_pec_sec = litres / irq_dt;116}117118_state.last_time_micros = now_us;119120// map amps to litres/hour121_state.current_amps = litres_pec_sec * (60*60);122123// map consumed_mah to consumed millilitres124_state.consumed_mah += litres * 1000;125126// map consumed_wh using fixed voltage of 1127_state.consumed_wh = _state.consumed_mah;128}129130#endif // AP_BATTERY_FUELFLOW_ENABLED131132133