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_FuelLevel_PWM.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_FUELLEVEL_PWM_ENABLED34#include <AP_HAL/AP_HAL.h>56#include "AP_BattMonitor_FuelLevel_PWM.h"78/*9"battery" monitor for liquid fuel level systems that give a PWM value indicating quantity of remaining fuel.1011Output is:1213- mAh remaining is fuel level in millilitres14- consumed mAh is in consumed millilitres15- fixed 1.0v voltage16*/17extern const AP_HAL::HAL& hal;1819/// Constructor20AP_BattMonitor_FuelLevel_PWM::AP_BattMonitor_FuelLevel_PWM(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms) :21AP_BattMonitor_Analog(mon, mon_state, params)22{23_state.voltage = 1.0; // show a fixed voltage of 1v2425// need to add check26_state.healthy = false;27}2829/*30read - read the "voltage" and "current"31*/32void AP_BattMonitor_FuelLevel_PWM::read()33{34if (!pwm_source.set_pin(_curr_pin, "FuelLevelPWM")) {35_state.healthy = false;36return;37}3839uint16_t pulse_width = pwm_source.get_pwm_us();4041/*42this driver assumes that CAPACITY is set to tank volume in millilitres.43*/44const uint16_t pwm_empty = 1100;45const uint16_t pwm_full = 1900;46const uint16_t pwm_buffer = 20;4748uint32_t now_us = AP_HAL::micros();4950// check for invalid pulse51if (pulse_width <= (pwm_empty - pwm_buffer)|| pulse_width >= (pwm_full + pwm_buffer)) {52_state.healthy = (now_us - _state.last_time_micros) < 250000U;53return;54}55pulse_width = constrain_int16(pulse_width, pwm_empty, pwm_full);56float proportion_full = (pulse_width - pwm_empty) / float(pwm_full - pwm_empty);57float proportion_used = 1.0 - proportion_full;5859_state.last_time_micros = now_us;60_state.healthy = true;6162// map consumed_mah to consumed millilitres63_state.consumed_mah = proportion_used * _params._pack_capacity;6465// map consumed_wh using fixed voltage of 166_state.consumed_wh = _state.consumed_mah;67}6869#endif // AP_BATTERY_FUELLEVEL_PWM_ENABLED707172