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_Analog.cpp
Views: 1798
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*14* Code by Charlie Johnson15*/1617#include "AP_BattMonitor_config.h"1819#if AP_BATTERY_FUELLEVEL_ANALOG_ENABLED2021#include <AP_HAL/AP_HAL.h>22#include <AP_Math/AP_Math.h>2324#include "AP_BattMonitor_FuelLevel_Analog.h"2526extern const AP_HAL::HAL& hal;2728const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = {2930// @Param: FL_VLT_MIN31// @DisplayName: Empty fuel level voltage32// @Description: The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.33// @Range: 0.01 1034// @Units: V35// @User: Advanced36AP_GROUPINFO("FL_VLT_MIN", 40, AP_BattMonitor_FuelLevel_Analog, _fuel_level_empty_voltage, 0.5),3738// @Param: FL_V_MULT39// @DisplayName: Fuel level voltage multiplier40// @Description: Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.41// @Range: 0.01 1042// @User: Advanced43AP_GROUPINFO("FL_V_MULT", 41, AP_BattMonitor_FuelLevel_Analog, _fuel_level_voltage_mult, 0.5),4445// @Param: FL_FLTR46// @DisplayName: Fuel level filter frequency47// @Description: Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.48// @Range: -1 149// @User: Advanced50// @Units: Hz51// @RebootRequired: True52AP_GROUPINFO("FL_FLTR", 42, AP_BattMonitor_FuelLevel_Analog, _fuel_level_filter_frequency, 0.3),5354// @Param: FL_PIN55// @DisplayName: Fuel level analog pin number56// @Description: Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".57// @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v158AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1),5960// @Param: FL_FF61// @DisplayName: First order term62// @Description: First order polynomial fit term63// @Range: -10 1064// @User: Advanced65AP_GROUPINFO("FL_FF", 45, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_first_order_coeff, 1),6667// @Param: FL_FS68// @DisplayName: Second order term69// @Description: Second order polynomial fit term70// @Range: -10 1071// @User: Advanced72AP_GROUPINFO("FL_FS", 46, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_second_order_coeff, 0),7374// @Param: FL_FT75// @DisplayName: Third order term76// @Description: Third order polynomial fit term77// @Range: -10 1078// @User: Advanced79AP_GROUPINFO("FL_FT", 47, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_third_order_coeff, 0),8081// @Param: FL_OFF82// @DisplayName: Offset term83// @Description: Offset polynomial fit term84// @Range: -10 1085// @User: Advanced86AP_GROUPINFO("FL_OFF", 48, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_offset, 0),8788// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS8990AP_GROUPEND91};9293// Constructor94AP_BattMonitor_FuelLevel_Analog::AP_BattMonitor_FuelLevel_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms) :95AP_BattMonitor_Backend(mon, mon_state, params)96{97AP_Param::setup_object_defaults(this, var_info);98_state.var_info = var_info;99100_analog_source = hal.analogin->channel(_pin);101102// create a low pass filter103// use a pole at 0.3 Hz if the filter is not being used104_voltage_filter.set_cutoff_frequency((_fuel_level_filter_frequency >= 0) ? _fuel_level_filter_frequency : 0.3f);105}106107/*108read - read the "voltage" and "current"109*/110void AP_BattMonitor_FuelLevel_Analog::read()111{112if (_analog_source == nullptr) {113return;114}115116if (!_analog_source->set_pin(_pin)) {117_state.healthy = false;118return;119}120_state.healthy = true;121122// get a dt and a timestamp123const uint32_t tnow = AP_HAL::micros();124const uint32_t dt_us = tnow - _state.last_time_micros;125126// get voltage from an ADC pin127const float raw_voltage = _analog_source->voltage_average();128129// Converting sensor reading to actual volume in tank in Litres (quadratic fit)130const float voltage =131(_fuel_fit_third_order_coeff * raw_voltage * raw_voltage * raw_voltage) +132(_fuel_fit_second_order_coeff * raw_voltage * raw_voltage) +133(_fuel_fit_first_order_coeff * raw_voltage) +134_fuel_fit_offset;135136const float filtered_voltage = _voltage_filter.apply(voltage, float(dt_us) * 1.0e-6f);137138// output the ADC voltage to the voltage field for easier calibration of sensors139// also output filtered voltage as a measure of tank slosh filtering140// this could be useful for tuning the LPF141const float &voltage_used = (_fuel_level_filter_frequency >= 0) ? filtered_voltage : voltage;142143_state.voltage = filtered_voltage;144145// this driver assumes that CAPACITY is set to tank volume in millilitres.146// _fuel_level_voltage_mult is calculated by the user as 1 / (full_voltage - empty_voltage)147const float fuel_level_ratio = (voltage_used - _fuel_level_empty_voltage) * _fuel_level_voltage_mult;148const float fuel_level_used_ratio = 1.0 - fuel_level_ratio;149150// map consumed_mah to consumed millilitres151_state.consumed_mah = fuel_level_used_ratio * _params._pack_capacity;152153_state.current_amps = 0;154155// map consumed_wh using fixed voltage of 1156_state.consumed_wh = _state.consumed_mah;157158// record time159_state.last_time_micros = tnow;160}161162#endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED163164165