CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp
Views: 1798
1
/*
2
* This file is free software: you can redistribute it and/or modify it
3
* under the terms of the GNU General Public License as published by the
4
* Free Software Foundation, either version 3 of the License, or
5
* (at your option) any later version.
6
*
7
* This file is distributed in the hope that it will be useful, but
8
* WITHOUT ANY WARRANTY; without even the implied warranty of
9
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10
* See the GNU General Public License for more details.
11
*
12
* You should have received a copy of the GNU General Public License along
13
* with this program. If not, see <http://www.gnu.org/licenses/>.
14
*
15
* Code by Charlie Johnson
16
*/
17
18
#include "AP_BattMonitor_config.h"
19
20
#if AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
21
22
#include <AP_HAL/AP_HAL.h>
23
#include <AP_Math/AP_Math.h>
24
25
#include "AP_BattMonitor_FuelLevel_Analog.h"
26
27
extern const AP_HAL::HAL& hal;
28
29
const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = {
30
31
// @Param: FL_VLT_MIN
32
// @DisplayName: Empty fuel level voltage
33
// @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.
34
// @Range: 0.01 10
35
// @Units: V
36
// @User: Advanced
37
AP_GROUPINFO("FL_VLT_MIN", 40, AP_BattMonitor_FuelLevel_Analog, _fuel_level_empty_voltage, 0.5),
38
39
// @Param: FL_V_MULT
40
// @DisplayName: Fuel level voltage multiplier
41
// @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.
42
// @Range: 0.01 10
43
// @User: Advanced
44
AP_GROUPINFO("FL_V_MULT", 41, AP_BattMonitor_FuelLevel_Analog, _fuel_level_voltage_mult, 0.5),
45
46
// @Param: FL_FLTR
47
// @DisplayName: Fuel level filter frequency
48
// @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.
49
// @Range: -1 1
50
// @User: Advanced
51
// @Units: Hz
52
// @RebootRequired: True
53
AP_GROUPINFO("FL_FLTR", 42, AP_BattMonitor_FuelLevel_Analog, _fuel_level_filter_frequency, 0.3),
54
55
// @Param: FL_PIN
56
// @DisplayName: Fuel level analog pin number
57
// @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".
58
// @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1
59
AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1),
60
61
// @Param: FL_FF
62
// @DisplayName: First order term
63
// @Description: First order polynomial fit term
64
// @Range: -10 10
65
// @User: Advanced
66
AP_GROUPINFO("FL_FF", 45, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_first_order_coeff, 1),
67
68
// @Param: FL_FS
69
// @DisplayName: Second order term
70
// @Description: Second order polynomial fit term
71
// @Range: -10 10
72
// @User: Advanced
73
AP_GROUPINFO("FL_FS", 46, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_second_order_coeff, 0),
74
75
// @Param: FL_FT
76
// @DisplayName: Third order term
77
// @Description: Third order polynomial fit term
78
// @Range: -10 10
79
// @User: Advanced
80
AP_GROUPINFO("FL_FT", 47, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_third_order_coeff, 0),
81
82
// @Param: FL_OFF
83
// @DisplayName: Offset term
84
// @Description: Offset polynomial fit term
85
// @Range: -10 10
86
// @User: Advanced
87
AP_GROUPINFO("FL_OFF", 48, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_offset, 0),
88
89
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
90
91
AP_GROUPEND
92
};
93
94
// Constructor
95
AP_BattMonitor_FuelLevel_Analog::AP_BattMonitor_FuelLevel_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params) :
96
AP_BattMonitor_Backend(mon, mon_state, params)
97
{
98
AP_Param::setup_object_defaults(this, var_info);
99
_state.var_info = var_info;
100
101
_analog_source = hal.analogin->channel(_pin);
102
103
// create a low pass filter
104
// use a pole at 0.3 Hz if the filter is not being used
105
_voltage_filter.set_cutoff_frequency((_fuel_level_filter_frequency >= 0) ? _fuel_level_filter_frequency : 0.3f);
106
}
107
108
/*
109
read - read the "voltage" and "current"
110
*/
111
void AP_BattMonitor_FuelLevel_Analog::read()
112
{
113
if (_analog_source == nullptr) {
114
return;
115
}
116
117
if (!_analog_source->set_pin(_pin)) {
118
_state.healthy = false;
119
return;
120
}
121
_state.healthy = true;
122
123
// get a dt and a timestamp
124
const uint32_t tnow = AP_HAL::micros();
125
const uint32_t dt_us = tnow - _state.last_time_micros;
126
127
// get voltage from an ADC pin
128
const float raw_voltage = _analog_source->voltage_average();
129
130
// Converting sensor reading to actual volume in tank in Litres (quadratic fit)
131
const float voltage =
132
(_fuel_fit_third_order_coeff * raw_voltage * raw_voltage * raw_voltage) +
133
(_fuel_fit_second_order_coeff * raw_voltage * raw_voltage) +
134
(_fuel_fit_first_order_coeff * raw_voltage) +
135
_fuel_fit_offset;
136
137
const float filtered_voltage = _voltage_filter.apply(voltage, float(dt_us) * 1.0e-6f);
138
139
// output the ADC voltage to the voltage field for easier calibration of sensors
140
// also output filtered voltage as a measure of tank slosh filtering
141
// this could be useful for tuning the LPF
142
const float &voltage_used = (_fuel_level_filter_frequency >= 0) ? filtered_voltage : voltage;
143
144
_state.voltage = filtered_voltage;
145
146
// this driver assumes that CAPACITY is set to tank volume in millilitres.
147
// _fuel_level_voltage_mult is calculated by the user as 1 / (full_voltage - empty_voltage)
148
const float fuel_level_ratio = (voltage_used - _fuel_level_empty_voltage) * _fuel_level_voltage_mult;
149
const float fuel_level_used_ratio = 1.0 - fuel_level_ratio;
150
151
// map consumed_mah to consumed millilitres
152
_state.consumed_mah = fuel_level_used_ratio * _params._pack_capacity;
153
154
_state.current_amps = 0;
155
156
// map consumed_wh using fixed voltage of 1
157
_state.consumed_wh = _state.consumed_mah;
158
159
// record time
160
_state.last_time_micros = tnow;
161
}
162
163
#endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
164
165