From 35f2dce575d755fb533d85db1705db391879b811 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 10 Nov 2024 14:31:39 +1100 Subject: [PATCH] AP_HAL_ESP32: re-order initialiser lines so -Werror=reorder will work --- libraries/AP_HAL_ESP32/AnalogIn.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/AnalogIn.cpp b/libraries/AP_HAL_ESP32/AnalogIn.cpp index 05487e62a0..7f027a31a3 100644 --- a/libraries/AP_HAL_ESP32/AnalogIn.cpp +++ b/libraries/AP_HAL_ESP32/AnalogIn.cpp @@ -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),