From 29c204c0bcf382c5f154a8d2f13c33f460a8220c Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 31 Aug 2023 16:14:25 +0100 Subject: [PATCH] AP_HAL_ChibiOS: correct hwdef generator battery scale --- .../AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py index 2f94816cf8..92a19e5d37 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py @@ -335,7 +335,7 @@ define HAL_BATT_VOLT_SCALE 11.0 f.write("%s BATT_CURRENT_SENS %s SCALE(1)\n" % (adc[1], name)) f.write('''define HAL_BATT_CURR_PIN %s define HAL_BATT_CURR_SCALE %.1f -''' % (get_ADC1_chan(mcu, adc[1]), int(settings['ibata_scale']) * 59.5 / 168 )) # scale taken from KakuteH7 +''' % (get_ADC1_chan(mcu, adc[1]), 10000 / int(settings['ibata_scale']))) elif (adc[3] == "ADC_RSSI"): f.write("%s RSSI_ADC %s\n" % (adc[1], name)) f.write("define BOARD_RSSI_ANA_PIN %s\n" % (get_ADC1_chan(mcu, adc[1])))