Use correct method to read config
[inav.git] / docs / Battery.md
blobf6bdbd5039133275e7cd0eb15c308e8f2f10be7a
1 # Battery Monitoring
3 INAV has a battery monitoring feature.  The voltage of the main battery can be measured by the system and used to trigger a low-battery warning [buzzer](Buzzer.md), on-board status LED flashing and LED strip patterns.
5 Low battery warnings can:
7 * Help ensure you have time to safely land the aircraft
8 * Help maintain the life and safety of your LiPo/LiFe batteries, which should not be discharged below manufacturer recommendations
10 Minimum and maximum cell voltages can be set, and these voltages are used to auto-detect the number of cells in the battery when it is first connected.
12 Per-cell monitoring is not supported, as we only use one ADC to read the battery voltage.
14 ## Supported targets
16 All targets support battery voltage monitoring unless stated.
18 ## Connections
20 When dealing with batteries **ALWAYS CHECK POLARITY!**
22 Measure expected voltages **first** and then connect to the flight controller.  Powering the flight controller with
23 incorrect voltage or reversed polarity will likely fry your flight controller. Ensure your flight controller
24 has a voltage divider capable of measuring your particular battery voltage.
25 On the first battery connection is always advisable to use a current limiter device to limit damages if something is wrong in the setup.
27 ### Sparky
29 See the [Sparky board chapter](Board%20-%20Sparky.md).
31 ## Voltage measurement
33 Enable the `VBAT` feature to enable the measurement of the battery voltage and the use of the voltage based OSD battery gauge, voltage based and energy based battery alarms.
35 ### Calibration
37 `vbat_scale` - Adjust this setting to match actual measured battery voltage to reported value. Increasing this value increases the measured voltage.
39 ### Voltage measurement source
41 Two voltage sources are available: raw voltage and sag compensated voltage. The raw voltage is the voltage directly measured at the battery while the sag compensated voltage is calculated by an algorithm aiming to provide a stable voltage source for gauges, telemetry and alarms. When the current drawn from a battery varies the provided voltage also varies due to the internal resistance of the battery, it is called sag. The sag can often trigger the battery alarms before the battery is empty and if you are relying on the battery voltage to know the charge state of your battery you have to land or cut the throttle to know the real, without load, battery voltage. The sag compensation algorithm simulates a battery with zero internal resistance and provides a stable reading independent from the drawn current.
43 You can select the voltage source used for battery alarms and telemetry with the `bat_voltage_source` setting. It can be set to either `RAW` for using raw battery voltage or `SAG_COMP` for using the calculated sag compensated voltage.
45 You can see an illustration of the sag compensation algorithm in action in the following graph:
47 ![Voltage graph](assets/images/sag_compensated_battery_voltage_plot.png)
49 ### Voltage based OSD gauge and alarms
51 Up to 3 battery profiles are supported. You can select the battery profile from the GUI, OSD menu, [stick commands](Controls.md) and CLI command `battery_profile n`. Each profile stores the following voltage settings:
53 `bat_cells` - Specify the number of cells of your battery. Allows the automatic selection of the battery profile when set to a value greater than 0. Set to 0 (default) for auto-detecting the number of cells (see next setting)
55 `vbat_cell_detect_voltage` - Maximum voltage per cell, used for auto-detecting the number of cells of the battery. Should be higher than maximum cell voltage to take into account possible drift in measured voltage and keep cell count detection accurate (0.01V unit, i.e. 430 = 4.30V)
57 `vbat_max_cell_voltage` - Maximum voltage per cell when the battery is fully charged. Used for the OSD voltage based battery gauge (0.01V unit, i.e. 420 = 4.20V)
59 `vbat_warning_cell_voltage` - Cell warning voltage. A cell voltage bellow this value triggers the first (short beeps) voltage based battery alarm if used and also the blinking of the OSD voltage indicator if the battery capacity is not used instead (see bellow) (0.01V unit, i.e. 370 = 3.70V)
61 `vbat_min_cell_voltage` - Cell minimum voltage. A cell voltage bellow this value triggers the second (long beeps) voltage based battery alarm if used and the OSD gauge will display 0% if the battery capacity is not used instead (see bellow) (0.01V unit, i.e. 350 = 3.50V)
63 e.g.
65 ```
66 battery_profile 1
67 set vbat_scale = 1100
68 set vbat_max_cell_voltage = 430
69 set vbat_warning_cell_voltage = 340
70 set vbat_min_cell_voltage = 330
71 ```
73 # Current Monitoring
75 Current monitoring (amperage) is supported by connecting a current meter to the appropriate current meter ADC input (see the documentation for your particular board).
77 When enabled, the following values calculated and used by the telemetry and OLED display subsystems:
78 * Amps
79 * mAh used
80 * Capacity remaining
82 ## Configuration
84 Enable current monitoring using the CLI command:
86 ```
87 feature CURRENT_METER
88 ```
90 Configure the current meter type using the `current_meter_type` settings here:
92 | Value | Sensor Type            |
93 | ----- | ---------------------- |
94 | 0     | None                   |
95 | 1     | ADC/hardware sensor    |
96 | 2     | Virtual sensor         |
98 Configure capacity using the `battery_capacity` setting, in mAh units.
100 If you're using an OSD that expects the multiwii current meter output value, then set `multiwii_current_meter_output` to `1` (this multiplies amperage sent to MSP by 10).
102 ### ADC Sensor
104 The current meter may need to be configured so the value read at the ADC input matches actual current draw.  Just like you need a voltmeter to correctly calibrate your voltage reading you also need an ammeter to calibrate the current sensor.
106 Use the following settings to adjust calibration:
108 `current_meter_scale`
109 `current_meter_offset`
111 ### Virtual Sensor
113 The virtual sensor uses the throttle position to calculate an estimated current value. This is useful when a real sensor is not available. The following settings adjust the virtual sensor calibration:
115 | Setting                       | Description                                              |
116 | ----------------------------- | -------------------------------------------------------- |
117 | `current_meter_scale`      | The throttle scaling factor [centiamps, i.e. 1/100th A]  |
118 | `current_meter_offset`     | The current at zero throttle (while disarmed) [centiamps, i.e. 1/100th A] |
120 There are two simple methods to tune these parameters:  one uses a battery charger and another depends on actual current measurements.
122 #### Tuning Using Actual Current Measurements
123 If you know your craft's current draw while disarmed (Imin) and at maximum throttle while armed (Imax), calculate the scaling factors as follows:
125 current_meter_scale = (Imax - Imin) * 100000 / (Tmax + (Tmax * Tmax / 50))
126 current_meter_offset = Imin * 100
128 Note: Tmax is maximum throttle offset (i.e. for `max_throttle` = 1850, Tmax = 1850 - 1000 = 850)
130 For example, assuming a maximum current of 34.2A, a minimum current of 2.8A, and a Tmax `max_throttle` = 1850:
132 current_meter_scale = (Imax - Imin) * 100000 / (Tmax + (Tmax * Tmax / 50))
133                     = (34.2 - 2.8) * 100000 / (850 + (850 * 850 / 50))
134                     = 205
135 current_meter_offset = Imin * 100 = 280
137 #### Tuning Using Battery Charger Measurement
138 If you cannot measure current draw directly, you can approximate it indirectly using your battery charger.  
139 However, note it may be difficult to adjust `current_meter_offset` using this method unless you can
140 measure the actual current draw with the craft disarmed.
142 Note:
143 + This method depends on the accuracy of your battery charger; results may vary.
144 + If you add or replace equipment that changes the in-flight current draw (e.g. video transmitter,
145   camera, gimbal, motors, prop pitch/sizes, ESCs, etc.), you should recalibrate.
147 The general method is:
149 1. Fully charge your flight battery
150 2. Fly your craft, using >50% of your battery pack capacity (estimated)
151 3. Note INAV's reported mAh draw
152 4. Re-charge your flight battery, noting the mAh charging data needed to restore the pack to fully charged
153 5. Adjust `current_meter_scale` to according to the formula given below
154 6. Repeat and test
156 Given (a) the reported mAh draw and the (b) mAh charging data, calculate a new `current_meter_scale` value as follows:
158 current_meter_scale = (reported_draw_mAh / charging_data_mAh) * old_current_meter_scale
160 For example, assuming:
161 + A INAV reported current draw of 1260 mAh
162 + Charging data to restore full charge of 1158 mAh
163 + A existing `current_meter_scale` value of 400 (the default)
165 Then the updated `current_meter_scale` is:
167 current_meter_scale = (reported_draw_mAh / charging_data_mAh) * old_current_meter_scale
168                     = (1260 / 1158) * 400
169                     = 435
172 ## Battery capacity monitoring
174 For the capacity monitoring to work you need a current sensor (`CURRENT_METER` feature). For monitoring energy in milliWatt hour you also need voltage measurement (`VBAT` feature). For best results the current and voltage readings have to be calibrated.
176 It is possible to display the remaining battery capacity in the OSD and also use the battery capacity thresholds (`battery_capacity_warning` and `battery_capacity_critical`) for battery alarms.
178 For the remaining battery capacity to be displayed users need to set the `battery_capacity` setting (>0) and the battery to be full when plugged in. If the `battery_capacity` setting is set to 0 the remaining battery capacity item in the OSD will display `NA` and the battery gauge will use an estimation based on the battery voltage otherwise it will display the remaining battery capacity down to the `battery_capacity_critical` setting (battery considered empty) and the battery gauge will be based on the remaining capacity. For the capacity thresholds to be used for alarms the `battery_capacity_warning` and `battery_capacity_critical` settings also needs to be set (>0) and the plugged in battery to be full when plugged in. The battery capacity settings unit can be set using the `battery_capacity_unit`. MilliAmpere hour and milliWatt hour units are supported. The value are absolute meaning that `battery_capacity_warning` is the battery capacity left when the battery is entering the `warning` state and `battery_capacity_critical` is the battery capacity left when the battery is considered empty and entering the `critical` state.
180 For the battery to be considered full the mean cell voltage of the battery needs to be above `vbat_max_cell_voltage - 140mV` (by default 4.1V). So a 3S battery will be considered full above 12.3V and a 4S battery above 16.24V. If the battery plugged in is not considered full the remaining battery capacity OSD item will show `NF` (Not Full).
182 For the remaining battery capacity and battery gauge to be the most precise (linear relative to throttle from full to empty) when using battery capacity monitoring users should use the milliWatt hour unit for the battery capacity settings.
184 ### Example configuration
187 set battery_capacity_unit = MAH         // battery capacity values are specified in milliAmpere hour
188 set battery_capacity = 2200             // battery capacity is 2200mAh
189 set battery_capacity_warning = 660      // the battery warning alarm will sound and the capacity related OSD items will blink when left capacity is less than 660 mAh (30% of battery capacity)
190 set battery_capacity_critical = 440     // the battery critical alarm will sound and the OSD battery gauge and remaining capacity item will be empty when left capacity is less than 440 mAh (20% of battery capacity)
193 Note that in this example even though your warning capacity (`battery_capacity_warning`) is set to 30% (660mAh), since 440mAh (`battery_capacity_critical`) is considered empty (0% left), the OSD capacity related items will only start to blink when the remaining battery percentage shown on the OSD is below 12%: (`battery_capacity_warning`-`battery_capacity_critical`)*100/(`battery_capacity`-`battery_capacity_critical`)=(660-440)*100/(2200-440)=12.5
196 ## Battery profiles
198 Up to 3 battery profiles are supported. You can select the battery profile from the GUI, OSD menu, [stick commands](Controls.md) and CLI command `battery_profile n`. Battery profiles store the following settings (see above for an explanation of each setting): 
199 - `bat_cells`
200 - `vbat_cell_detect_voltage`
201 - `vbat_max_cell_voltage`
202 - `vbat_warning_cell_voltage`
203 - `vbat_min_cell_voltage`
204 - `battery_capacity_unit`
205 - `battery_capacity`
206 - `battery_capacity_warning`
207 - `battery_capacity_critical`
208 - `throttle_idle`
209 - `throttle_scale`
210 - `turtle_mode_power_factor`
211 - `nav_fw_cruise_thr`
212 - `nav_fw_min_thr`
213 - `nav_fw_max_thr`
214 - `nav_fw_pitch2thr`
215 - `nav_fw_launch_thr`
216 - `nav_fw_launch_idle_thr`
217 - `failsafe_throttle`
218 - `nav_mc_hover_thr`
220 To enable the automatic battery profile switching based on battery voltage enable the `BAT_PROF_AUTOSWITCH` feature. For a profile to be automatically selected the number of cells of the battery needs to be specified (>0).
222 ### Battery profiles configuration examples
224 #### Simple example
226 In this example we want to use two different type of batteries for the same aircraft and switch manually between them. The first battery is a Li-Po (4.20V/cell) and the second battery is a Li-Ion (4.10V/cell).
229 battery_profile 1
231 set bat_cells = 0
232 set vbat_max_cell_voltage = 420
233 set vbat_warning_cell_voltage = 370
234 set vbat_min_cell_voltage = 340
237 battery_profile 2
239 set bat_cells = 0
240 set vbat_max_cell_voltage = 410
241 set vbat_warning_cell_voltage = 280
242 set vbat_min_cell_voltage = 250
245 #### Simple example with automatic profile switching
247 In this example we want to use two different batteries for the same aircraft and automatically switch between them when the battery is plugged in. The first battery is a Li-Po 2200mAh 3S and the second battery is a LiPo 1500mAh 4S. Since the INAV defaults for the cell detection voltage and max voltage are adequate for standard LiPo batteries they will not be modified. The warning and minimum voltage are not modified either in this example but you can set them to the value you like. Since we are using battery capacities only the warning voltage (kept at default in this example) will be used and only for triggering the battery voltage indicator blinking in the OSD.
250 feature BAT_PROF_AUTOSWITCH
253 battery_profile 1
255 set bat_cells = 3
256 set battery_capacity_unit = MAH
257 set battery_capacity = 2200
258 set battery_capacity_warning = 440
259 set battery_capacity_critical = 220
262 battery_profile 2
264 set bat_cells = 4
265 set battery_capacity_unit = MAH
266 set battery_capacity = 1500
267 set battery_capacity_warning = 300
268 set battery_capacity_critical = 150
271 #### Advanced automatic switching example
273 Profile 1 is for a 3S 2200mAh Li-Po pack (max 4.20V/cell), profile 2 for a 3S 4000mAh Li-Ion pack (max 4.10V/cell) and profile 3 for a 4S 1500mAh Li-Po pack (max 4.20V/cell).
274 With this configuration if the battery plugged in is less than 12.36V (3 x 4.12) the profile 2 will be automatically selected else if the battery voltage is less than 12.66V (3 x 4.22) the profile 1 will be automatically selected else if the battery voltage is less 17.20V (4 x 4.3) the profile 3 will be automatically selected. If a matching profile can't be found the last selected profile is used.
277 feature BAT_PROF_AUTOSWITCH
280 battery_profile 1
282 set bat_cells = 3
283 set vbat_cell_detect_voltage = 422
284 set vbat_max_cell_voltage = 420
285 set vbat_warning_cell_voltage = 350
286 set vbat_min_cell_voltage = 330
287 set battery_capacity = 2200
288 set battery_capacity_warning = 440
289 set battery_capacity_critical = 220
292 battery_profile 2
294 set bat_cells = 3
295 set vbat_cell_detect_voltage = 412
296 set vbat_max_cell_voltage = 410
297 set vbat_warning_cell_voltage = 300
298 set vbat_min_cell_voltage = 280
299 set battery_capacity = 4000
300 set battery_capacity_warning = 800
301 set battery_capacity_critical = 400
304 battery_profile 3
306 set bat_cells = 4
307 set vbat_cell_detect_voltage = 430
308 set vbat_max_cell_voltage = 420
309 set vbat_warning_cell_voltage = 350
310 set vbat_min_cell_voltage = 330
311 set battery_capacity = 1500
312 set battery_capacity_warning = 300
313 set battery_capacity_critical = 150
316 #### Change control profile based on battery profile
318 You can change the control profile, automatically, based on the battery profile. This allows for fine tuning of each power choice.
321 feature BAT_PROF_AUTOSWITCH
324 battery_profile 1
326 set bat_cells = 3
327 set controlrate_profile = 1
329 battery_profile 2
331 set bat_cells = 4
332 set controlrate_profile = 2
335 ## Remaining flight time and flight distance estimation
337 The estimated remaining flight time and flight distance estimations can be displayed on the OSD (for fixed wing only for the moment). They are calculated from the GPS distance from home, remaining battery capacity and average power draw. They are taking into account the requested altitude change and heading to home change after altitude change following the switch to RTH. They are also taking into account the estimated wind if `osd_estimations_wind_compensation` is set to `ON`. When the timer and distance indicator reach 0 they will blink and you need to go home in a straight line manually or by engaging RTH. You should be left with at least `rth_energy_margin`% of battery left when arriving home if the cruise speed and power are set correctly (see bellow).
339 To use this feature the following conditions need to be met:
340 - The `VBAT`, `CURRENT_METER` and `GPS` features need to be enabled
341 - The battery capacity needs to be specified in mWh (`battery_capacity` setting > 0 and `battery_capacity_unit` set to `MWH`)
342 - The average ground speed of the aircraft without wind at cruise throttle needs to be set (`nav_fw_cruise_speed` setting in cm/s)
343 - The average power draw at zero throttle needs to be specified (`idle_power` setting in 0.01W unit)
344 - The average power draw at cruise throttle needs to be specified (`cruise_power` setting in 0.01W unit)
345 - The battery needs to be full when plugged in (voltage >= (`vbat_max_cell_voltage` - 100mV) * cells)
347 It is advised to set `nav_fw_cruise_speed` a bit lower than the real speed and `cruise_power` 10% higher than the power at cruise throttle to ensure variations in throttle during cruise won't cause the aircraft to draw more energy than estimated.
349 If `---` is displayed during flight instead of the remaining flight time/distance it means at least one of the above conditions aren't met. If the OSD element is blinking and the digits are replaced by the horizontal wind symbol it means that the estimated horizontal wind is too strong to be able to return home at `nav_fw_cruise_speed`.
351 ## Automatic throttle compensation based on battery voltage
353 This features aims to compensate the throttle to get constant thrust with the same throttle request despite the battery voltage going down during flight. It can be used by enabling the `THR_VBAT_COMP` feature. This feature needs the sag compensated voltage which needs a current sensor (real or virtual) to be calculated.
355 It is working like this: `used_throttle = requested_throttle * (1 + (battery_full_voltage / sag_compensated_voltage - 1) * thr_comp_weight)`.
357 The default `thr_comp_weight` of 1 should be close to ideal but if you want to tune this feature you need to find the difference in throttle value to achieve the same thrust (same power) when your battery is full and when your battery is almost empty then set `thr_comp_weight` to `(empty_battery_throttle / full_battery_throttle - 1) / (battery_full_voltage / battery_empty_sag_compensated_voltage - 1)`
359 Example:
360   If the drawn power is 100W when the battery is full (12.6V) with 53% throttle and the drawn power is 100W with 58% throttle when the battery is almost empty with the sag compensated voltage being 11.0V `thr_comp_weight` needs to be set to this value to compensate the throttle automatically:
361   `(58 / 53 - 1) / (12.6 / 11.0 - 1) = 0.649`
363 Known limitation: it doesn't work in 3D mode (3D feature)