mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: fix voltage sensor connected to fmu adc
This commit is contained in:
parent
e36231d547
commit
e5988f7153
|
@ -297,6 +297,11 @@ void AnalogIn::_timer_tick(void)
|
|||
// voltage_average_ratiometric()
|
||||
_board_voltage = buf_adc[i] * pin_config[i].scaling;
|
||||
}
|
||||
#endif
|
||||
#ifdef FMU_SERVORAIL_ADC_CHAN
|
||||
if (pin_config[i].channel == FMU_SERVORAIL_ADC_CHAN) {
|
||||
_servorail_voltage = buf_adc[i] * pin_config[i].scaling;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -1204,6 +1204,9 @@ def write_ADC_config(f):
|
|||
if p.label == 'VDD_5V_SENS':
|
||||
f.write('#define ANALOG_VCC_5V_PIN %u\n' % chan)
|
||||
f.write('#define HAL_HAVE_BOARD_VOLTAGE 1\n')
|
||||
if p.label == 'FMU_SERVORAIL_VCC_SENS':
|
||||
f.write('#define FMU_SERVORAIL_ADC_CHAN %u\n' % chan)
|
||||
f.write('#define HAL_HAVE_SERVO_VOLTAGE 1\n')
|
||||
adc_chans.append((chan, scale, p.label, p.portpin))
|
||||
adc_chans = sorted(adc_chans)
|
||||
vdd = get_config('STM32_VDD')
|
||||
|
|
Loading…
Reference in New Issue