mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: re-order initialiser lines so -Werror=reorder will work
This commit is contained in:
parent
ebe9a75a66
commit
cc9279713a
|
@ -31,7 +31,8 @@ using namespace ESP32;
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
DeviceBus::DeviceBus(uint8_t _thread_priority) :
|
DeviceBus::DeviceBus(uint8_t _thread_priority) :
|
||||||
thread_priority(_thread_priority), semaphore()
|
semaphore(),
|
||||||
|
thread_priority(_thread_priority)
|
||||||
{
|
{
|
||||||
#ifdef BUSDEBUG
|
#ifdef BUSDEBUG
|
||||||
printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__);
|
printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__);
|
||||||
|
|
|
@ -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) :
|
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),
|
_retries(10),
|
||||||
_address(address),
|
_address(address)
|
||||||
bus(I2CDeviceManager::businfo[busnum])
|
|
||||||
{
|
{
|
||||||
set_device_bus(busnum);
|
set_device_bus(busnum);
|
||||||
set_device_address(address);
|
set_device_address(address);
|
||||||
|
|
Loading…
Reference in New Issue