Merge branch 'master' into abo_stats_pages_auto_swap
[inav.git] / src / main / sensors / battery.h
blob94201fb28cfa7f4f9069321421ed190f5be453bc
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #include "config/parameter_group.h"
21 #include "drivers/time.h"
23 #ifndef VBAT_SCALE_DEFAULT
24 #define VBAT_SCALE_DEFAULT 1100
25 #endif
26 #define VBAT_SCALE_MIN 0
27 #define VBAT_SCALE_MAX 65535
29 #ifndef CURRENT_METER_SCALE
30 #define CURRENT_METER_SCALE 400 // for Allegro ACS758LCB-100U (40mV/A)
31 #endif
33 #ifndef CURRENT_METER_OFFSET
34 #define CURRENT_METER_OFFSET 0
35 #endif
37 #ifndef MAX_BATTERY_PROFILE_COUNT
38 #define MAX_BATTERY_PROFILE_COUNT 3
39 #endif
41 typedef enum {
42 CURRENT_SENSOR_NONE = 0,
43 CURRENT_SENSOR_ADC,
44 CURRENT_SENSOR_VIRTUAL,
45 CURRENT_SENSOR_ESC,
46 CURRENT_SENSOR_MAX = CURRENT_SENSOR_VIRTUAL
47 } currentSensor_e;
49 typedef enum {
50 VOLTAGE_SENSOR_NONE = 0,
51 VOLTAGE_SENSOR_ADC,
52 VOLTAGE_SENSOR_ESC
53 } voltageSensor_e;
55 typedef enum {
56 BAT_CAPACITY_UNIT_MAH,
57 BAT_CAPACITY_UNIT_MWH,
58 } batCapacityUnit_e;
60 typedef struct {
61 uint8_t profile_index;
62 uint16_t max_voltage;
63 } profile_comp_t;
65 typedef enum {
66 BAT_VOLTAGE_RAW,
67 BAT_VOLTAGE_SAG_COMP
68 } batVoltageSource_e;
70 typedef struct batteryMetersConfig_s {
72 #ifdef USE_ADC
73 struct {
74 uint16_t scale;
75 voltageSensor_e type;
76 } voltage;
77 #endif
79 struct {
80 int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
81 int16_t offset; // offset of the current sensor in millivolt steps
82 currentSensor_e type; // type of current meter used, either ADC or virtual
83 } current;
85 batVoltageSource_e voltageSource;
87 uint32_t cruise_power; // power drawn by the motor(s) at cruise throttle/speed (cW)
88 uint16_t idle_power; // power drawn by the system when the motor(s) are stopped (cW)
89 uint8_t rth_energy_margin; // Energy that should be left after RTH (%), used for remaining time/distance before RTH
91 float throttle_compensation_weight;
93 } batteryMetersConfig_t;
95 typedef struct batteryProfile_s {
97 #ifdef USE_ADC
98 uint8_t cells;
100 struct {
101 uint16_t cellDetect; // maximum voltage per cell, used for auto-detecting battery cell count in 0.01V units, default is 430 (4.3V)
102 uint16_t cellMax; // maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 421 (4.21V)
103 uint16_t cellMin; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V)
104 uint16_t cellWarning; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V)
105 } voltage;
106 #endif
108 struct {
109 uint32_t value; // mAh or mWh (see capacity.unit)
110 uint32_t warning; // mAh or mWh (see capacity.unit)
111 uint32_t critical; // mAh or mWh (see capacity.unit)
112 batCapacityUnit_e unit; // Describes unit of capacity.value, capacity.warning and capacity.critical
113 } capacity;
115 } batteryProfile_t;
117 PG_DECLARE(batteryMetersConfig_t, batteryMetersConfig);
118 PG_DECLARE_ARRAY(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles);
120 extern const batteryProfile_t *currentBatteryProfile;
122 typedef enum {
123 BATTERY_OK = 0,
124 BATTERY_WARNING,
125 BATTERY_CRITICAL,
126 BATTERY_NOT_PRESENT
127 } batteryState_e;
130 uint16_t batteryAdcToVoltage(uint16_t src);
131 batteryState_e getBatteryState(void);
132 bool batteryWasFullWhenPluggedIn(void);
133 bool batteryUsesCapacityThresholds(void);
134 void batteryInit(void);
135 void setBatteryProfile(uint8_t profileIndex);
136 void activateBatteryProfile(void);
137 void batteryDisableProfileAutoswitch(void);
139 bool isBatteryVoltageConfigured(void);
140 bool isPowerSupplyImpedanceValid(void);
141 uint16_t getBatteryVoltage(void);
142 uint16_t getBatteryRawVoltage(void);
143 uint16_t getBatterySagCompensatedVoltage(void);
144 uint16_t getBatteryWarningVoltage(void);
145 uint8_t getBatteryCellCount(void);
146 uint16_t getBatteryRawAverageCellVoltage(void);
147 uint16_t getBatteryAverageCellVoltage(void);
148 uint16_t getBatterySagCompensatedAverageCellVoltage(void);
149 uint32_t getBatteryRemainingCapacity(void);
150 uint16_t getPowerSupplyImpedance(void);
152 bool isAmperageConfigured(void);
153 int16_t getAmperage(void);
154 int32_t getPower(void);
155 int32_t getMAhDrawn(void);
156 int32_t getMWhDrawn(void);
158 #ifdef USE_ADC
159 void batteryUpdate(timeUs_t timeDelta);
160 void sagCompensatedVBatUpdate(timeUs_t currentTime, timeUs_t timeDelta);
161 void powerMeterUpdate(timeUs_t timeDelta);
162 #endif
164 void currentMeterUpdate(timeUs_t timeDelta);
166 uint8_t calculateBatteryPercentage(void);
167 float calculateThrottleCompensationFactor(void);
168 int32_t calculateAveragePower(void);
169 int32_t calculateAverageEfficiency(void);
170 int32_t heatLossesCompensatedPower(int32_t power);