AP_HAL_ChibiOS: correct hwdef generator battery scale

This commit is contained in:
Andy Piper 2023-08-31 16:14:25 +01:00 committed by Andrew Tridgell
parent d179103c67
commit 29c204c0bc

View File

@ -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("%s BATT_CURRENT_SENS %s SCALE(1)\n" % (adc[1], name))
f.write('''define HAL_BATT_CURR_PIN %s f.write('''define HAL_BATT_CURR_PIN %s
define HAL_BATT_CURR_SCALE %.1f 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"): elif (adc[3] == "ADC_RSSI"):
f.write("%s RSSI_ADC %s\n" % (adc[1], name)) 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]))) f.write("define BOARD_RSSI_ANA_PIN %s\n" % (get_ADC1_chan(mcu, adc[1])))