From cc9279713a4fe8f6310814dbf7bcf058d9dd3088 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 22 Sep 2024 10:37:45 +1000 Subject: [PATCH] AP_HAL_ESP32: re-order initialiser lines so -Werror=reorder will work --- libraries/AP_HAL_ESP32/DeviceBus.cpp | 3 ++- libraries/AP_HAL_ESP32/I2CDevice.cpp | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ESP32/DeviceBus.cpp b/libraries/AP_HAL_ESP32/DeviceBus.cpp index 092ee9b00b..12a46fbb61 100644 --- a/libraries/AP_HAL_ESP32/DeviceBus.cpp +++ b/libraries/AP_HAL_ESP32/DeviceBus.cpp @@ -31,7 +31,8 @@ using namespace ESP32; extern const AP_HAL::HAL& hal; DeviceBus::DeviceBus(uint8_t _thread_priority) : - thread_priority(_thread_priority), semaphore() + semaphore(), + thread_priority(_thread_priority) { #ifdef BUSDEBUG printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__); diff --git a/libraries/AP_HAL_ESP32/I2CDevice.cpp b/libraries/AP_HAL_ESP32/I2CDevice.cpp index 149d60eb05..e2bcc9071e 100644 --- a/libraries/AP_HAL_ESP32/I2CDevice.cpp +++ b/libraries/AP_HAL_ESP32/I2CDevice.cpp @@ -59,9 +59,9 @@ I2CDeviceManager::I2CDeviceManager(void) } I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms) : + bus(I2CDeviceManager::businfo[busnum]), _retries(10), - _address(address), - bus(I2CDeviceManager::businfo[busnum]) + _address(address) { set_device_bus(busnum); set_device_address(address);