mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_QURT: re-order initialiser lines so -Werror=reorder will work
This commit is contained in:
parent
27df5e0479
commit
3d4b57cd4a
|
@ -27,7 +27,8 @@ using namespace QURT;
|
|||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
DeviceBus::DeviceBus(AP_HAL::Scheduler::priority_base _thread_priority) :
|
||||
thread_priority(_thread_priority), semaphore()
|
||||
semaphore(),
|
||||
thread_priority(_thread_priority)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -41,8 +41,8 @@ I2CDeviceManager::I2CDeviceManager(void)
|
|||
}
|
||||
|
||||
I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms) :
|
||||
_address(address),
|
||||
bus(I2CDeviceManager::businfo[busnum])
|
||||
bus(I2CDeviceManager::businfo[busnum]),
|
||||
_address(address)
|
||||
{
|
||||
if (busnum >= ARRAY_SIZE(i2c_bus_ids)) {
|
||||
bus.fd = -1;
|
||||
|
|
Loading…
Reference in New Issue