Merge pull request #10471 from etracer65/current_meter_div0_fix
[betaflight.git] / src / main / sensors / current.c
blob0c12e2f1b3ff4eb45d5fc5ff0165fb4e4a3834ae
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include "stdbool.h"
22 #include "stdint.h"
23 #include "string.h"
25 #include "platform.h"
27 #include "build/build_config.h"
28 #include "build/debug.h"
30 #include "common/maths.h"
31 #include "common/utils.h"
32 #include "common/filter.h"
34 #include "drivers/adc.h"
36 #include "pg/pg.h"
37 #include "pg/pg_ids.h"
39 #include "sensors/adcinternal.h"
40 #include "sensors/battery.h"
41 #include "sensors/esc_sensor.h"
43 #include "current.h"
45 const char * const currentMeterSourceNames[CURRENT_METER_COUNT] = {
46 "NONE", "ADC", "VIRTUAL", "ESC", "MSP"
49 const uint8_t currentMeterIds[] = {
50 CURRENT_METER_ID_BATTERY_1,
51 #ifdef USE_VIRTUAL_CURRENT_METER
52 CURRENT_METER_ID_VIRTUAL_1,
53 #endif
54 #ifdef USE_ESC_SENSOR
55 CURRENT_METER_ID_ESC_COMBINED_1,
56 CURRENT_METER_ID_ESC_MOTOR_1,
57 CURRENT_METER_ID_ESC_MOTOR_2,
58 CURRENT_METER_ID_ESC_MOTOR_3,
59 CURRENT_METER_ID_ESC_MOTOR_4,
60 CURRENT_METER_ID_ESC_MOTOR_5,
61 CURRENT_METER_ID_ESC_MOTOR_6,
62 CURRENT_METER_ID_ESC_MOTOR_7,
63 CURRENT_METER_ID_ESC_MOTOR_8,
64 CURRENT_METER_ID_ESC_MOTOR_9,
65 CURRENT_METER_ID_ESC_MOTOR_10,
66 CURRENT_METER_ID_ESC_MOTOR_11,
67 CURRENT_METER_ID_ESC_MOTOR_12,
68 #endif
69 #ifdef USE_MSP_CURRENT_METER
70 CURRENT_METER_ID_MSP_1,
71 #endif
74 const uint8_t supportedCurrentMeterCount = ARRAYLEN(currentMeterIds);
77 // ADC/Virtual/ESC/MSP shared
80 void currentMeterReset(currentMeter_t *meter)
82 meter->amperage = 0;
83 meter->amperageLatest = 0;
84 meter->mAhDrawn = 0;
88 // ADC/Virtual shared
91 static pt1Filter_t adciBatFilter;
93 #ifndef CURRENT_METER_SCALE_DEFAULT
94 #define CURRENT_METER_SCALE_DEFAULT 400 // for Allegro ACS758LCB-100U (40mV/A)
95 #endif
97 #ifndef CURRENT_METER_OFFSET_DEFAULT
98 #define CURRENT_METER_OFFSET_DEFAULT 0
99 #endif
101 PG_REGISTER_WITH_RESET_TEMPLATE(currentSensorADCConfig_t, currentSensorADCConfig, PG_CURRENT_SENSOR_ADC_CONFIG, 0);
103 PG_RESET_TEMPLATE(currentSensorADCConfig_t, currentSensorADCConfig,
104 .scale = CURRENT_METER_SCALE_DEFAULT,
105 .offset = CURRENT_METER_OFFSET_DEFAULT,
108 #ifdef USE_VIRTUAL_CURRENT_METER
109 PG_REGISTER(currentSensorVirtualConfig_t, currentSensorVirtualConfig, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, 0);
110 #endif
112 static int32_t currentMeterADCToCentiamps(const uint16_t src)
115 const currentSensorADCConfig_t *config = currentSensorADCConfig();
117 int32_t millivolts = ((uint32_t)src * getVrefMv()) / 4096;
118 // y=x/m+b m is scale in (mV/10A) and b is offset in (mA)
119 int32_t centiAmps = config->scale ? (millivolts * 10000 / (int32_t)config->scale + (int32_t)config->offset) / 10 : 0;
121 DEBUG_SET(DEBUG_CURRENT_SENSOR, 0, millivolts);
122 DEBUG_SET(DEBUG_CURRENT_SENSOR, 1, centiAmps);
124 return centiAmps; // Returns Centiamps to maintain compatability with the rest of the code
127 #if defined(USE_ADC) || defined(USE_VIRTUAL_CURRENT_METER)
128 static void updateCurrentmAhDrawnState(currentMeterMAhDrawnState_t *state, int32_t amperageLatest, int32_t lastUpdateAt)
130 state->mAhDrawnF = state->mAhDrawnF + (amperageLatest * lastUpdateAt / (100.0f * 1000 * 3600));
131 state->mAhDrawn = state->mAhDrawnF;
133 #endif
136 // ADC
139 currentMeterADCState_t currentMeterADCState;
141 void currentMeterADCInit(void)
143 memset(&currentMeterADCState, 0, sizeof(currentMeterADCState_t));
144 pt1FilterInit(&adciBatFilter, pt1FilterGain(GET_BATTERY_LPF_FREQUENCY(batteryConfig()->ibatLpfPeriod), HZ_TO_INTERVAL(50)));
147 void currentMeterADCRefresh(int32_t lastUpdateAt)
149 #ifdef USE_ADC
150 const uint16_t iBatSample = adcGetChannel(ADC_CURRENT);
151 currentMeterADCState.amperageLatest = currentMeterADCToCentiamps(iBatSample);
152 currentMeterADCState.amperage = currentMeterADCToCentiamps(pt1FilterApply(&adciBatFilter, iBatSample));
154 updateCurrentmAhDrawnState(&currentMeterADCState.mahDrawnState, currentMeterADCState.amperageLatest, lastUpdateAt);
155 #else
156 UNUSED(lastUpdateAt);
157 UNUSED(currentMeterADCToCentiamps);
159 currentMeterADCState.amperageLatest = 0;
160 currentMeterADCState.amperage = 0;
161 #endif
164 void currentMeterADCRead(currentMeter_t *meter)
166 meter->amperageLatest = currentMeterADCState.amperageLatest;
167 meter->amperage = currentMeterADCState.amperage;
168 meter->mAhDrawn = currentMeterADCState.mahDrawnState.mAhDrawn;
170 DEBUG_SET(DEBUG_CURRENT_SENSOR, 2, meter->amperageLatest);
171 DEBUG_SET(DEBUG_CURRENT_SENSOR, 3, meter->mAhDrawn);
175 // VIRTUAL
178 #ifdef USE_VIRTUAL_CURRENT_METER
179 currentSensorVirtualState_t currentMeterVirtualState;
181 void currentMeterVirtualInit(void)
183 memset(&currentMeterVirtualState, 0, sizeof(currentSensorVirtualState_t));
186 void currentMeterVirtualRefresh(int32_t lastUpdateAt, bool armed, bool throttleLowAndMotorStop, int32_t throttleOffset)
188 currentMeterVirtualState.amperage = (int32_t)currentSensorVirtualConfig()->offset;
189 if (armed) {
190 if (throttleLowAndMotorStop) {
191 throttleOffset = 0;
194 int throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50); // FIXME magic number 50, 50hz?
195 currentMeterVirtualState.amperage += throttleFactor * (int32_t)currentSensorVirtualConfig()->scale / 1000;
197 updateCurrentmAhDrawnState(&currentMeterVirtualState.mahDrawnState, currentMeterVirtualState.amperage, lastUpdateAt);
200 void currentMeterVirtualRead(currentMeter_t *meter)
202 meter->amperageLatest = currentMeterVirtualState.amperage;
203 meter->amperage = currentMeterVirtualState.amperage;
204 meter->mAhDrawn = currentMeterVirtualState.mahDrawnState.mAhDrawn;
206 #endif
209 // ESC
212 #ifdef USE_ESC_SENSOR
213 currentMeterESCState_t currentMeterESCState;
215 void currentMeterESCInit(void)
217 memset(&currentMeterESCState, 0, sizeof(currentMeterESCState_t));
220 void currentMeterESCRefresh(int32_t lastUpdateAt)
222 UNUSED(lastUpdateAt);
224 escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED);
225 if (escData && escData->dataAge <= ESC_BATTERY_AGE_MAX) {
226 currentMeterESCState.amperage = escData->current + escSensorConfig()->offset / 10;
227 currentMeterESCState.mAhDrawn = escData->consumption + escSensorConfig()->offset * millis() / (1000.0f * 3600);
228 } else {
229 currentMeterESCState.amperage = 0;
230 currentMeterESCState.mAhDrawn = 0;
234 void currentMeterESCReadCombined(currentMeter_t *meter)
236 meter->amperageLatest = currentMeterESCState.amperage;
237 meter->amperage = currentMeterESCState.amperage;
238 meter->mAhDrawn = currentMeterESCState.mAhDrawn;
241 void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter)
243 escSensorData_t *escData = getEscSensorData(motorNumber);
244 if (escData && escData->dataAge <= ESC_BATTERY_AGE_MAX) {
245 meter->amperage = escData->current;
246 meter->amperageLatest = escData->current;
247 meter->mAhDrawn = escData->consumption;
248 } else {
249 currentMeterReset(meter);
252 #endif
255 #ifdef USE_MSP_CURRENT_METER
256 #include "common/streambuf.h"
258 #include "msp/msp_protocol.h"
259 #include "msp/msp_serial.h"
261 currentMeterMSPState_t currentMeterMSPState;
263 void currentMeterMSPSet(uint16_t amperage, uint16_t mAhDrawn)
265 // We expect the FC's MSP_ANALOG response handler to call this function
266 currentMeterMSPState.amperage = amperage;
267 currentMeterMSPState.mAhDrawn = mAhDrawn;
270 void currentMeterMSPInit(void)
272 memset(&currentMeterMSPState, 0, sizeof(currentMeterMSPState_t));
275 void currentMeterMSPRefresh(timeUs_t currentTimeUs)
277 // periodically request MSP_ANALOG
278 static timeUs_t streamRequestAt = 0;
279 if (cmp32(currentTimeUs, streamRequestAt) > 0) {
280 streamRequestAt = currentTimeUs + ((1000 * 1000) / 10); // 10hz
282 mspSerialPush(SERIAL_PORT_NONE, MSP_ANALOG, NULL, 0, MSP_DIRECTION_REQUEST);
286 void currentMeterMSPRead(currentMeter_t *meter)
288 meter->amperageLatest = currentMeterMSPState.amperage;
289 meter->amperage = currentMeterMSPState.amperage;
290 meter->mAhDrawn = currentMeterMSPState.mAhDrawn;
292 #endif
295 // API for current meters using IDs
297 // This API is used by MSP, for configuration/status.
300 void currentMeterRead(currentMeterId_e id, currentMeter_t *meter)
302 if (id == CURRENT_METER_ID_BATTERY_1) {
303 currentMeterADCRead(meter);
305 #ifdef USE_VIRTUAL_CURRENT_METER
306 else if (id == CURRENT_METER_ID_VIRTUAL_1) {
307 currentMeterVirtualRead(meter);
309 #endif
310 #ifdef USE_MSP_CURRENT_METER
311 else if (id == CURRENT_METER_ID_MSP_1) {
312 currentMeterMSPRead(meter);
314 #endif
315 #ifdef USE_ESC_SENSOR
316 else if (id == CURRENT_METER_ID_ESC_COMBINED_1) {
317 currentMeterESCReadCombined(meter);
319 else if (id >= CURRENT_METER_ID_ESC_MOTOR_1 && id <= CURRENT_METER_ID_ESC_MOTOR_20 ) {
320 int motor = id - CURRENT_METER_ID_ESC_MOTOR_1;
321 currentMeterESCReadMotor(motor, meter);
323 #endif
324 else {
325 currentMeterReset(meter);