AP_HAL_ESP32: re-order initialiser lines so -Werror=reorder will work

This commit is contained in:
Peter Barker 2024-11-10 14:31:39 +11:00 committed by Peter Barker
parent b7ccee5ebe
commit 35f2dce575
1 changed files with 1 additions and 1 deletions

View File

@ -141,8 +141,8 @@ void adc_calibration_deinit(adc_cali_handle_t handle)
//ardupin is the ardupilot assigned number, starting from 1-8(max)
AnalogSource::AnalogSource(int16_t ardupin, adc_channel_t adc_channel, float scaler, float initial_value) :
_ardupin(ardupin),
_adc_channel(adc_channel),
_ardupin(ardupin),
_scaler(scaler),
_value(initial_value),
_latest_value(initial_value),