mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 00:43:58 -04:00
AP_HAL_QURT: add get_device_ptr to HAL I2CDevice API
This commit is contained in:
parent
07d5938d68
commit
049ad3928d
@ -98,17 +98,16 @@ bool I2CDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint3
|
||||
return bus.adjust_timer(h, period_usec);
|
||||
}
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
||||
I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
|
||||
uint32_t bus_clock,
|
||||
bool use_smbus,
|
||||
uint32_t timeout_ms)
|
||||
AP_HAL::I2CDevice *
|
||||
I2CDeviceManager::get_device_ptr(uint8_t bus, uint8_t address,
|
||||
uint32_t bus_clock,
|
||||
bool use_smbus,
|
||||
uint32_t timeout_ms)
|
||||
{
|
||||
if (bus >= ARRAY_SIZE(i2c_bus_ids)) {
|
||||
return AP_HAL::OwnPtr<AP_HAL::I2CDevice>(nullptr);
|
||||
return nullptr;
|
||||
}
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms));
|
||||
return dev;
|
||||
return new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -111,7 +111,7 @@ public:
|
||||
return static_cast<I2CDeviceManager*>(i2c_mgr);
|
||||
}
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address,
|
||||
AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address,
|
||||
uint32_t bus_clock=100000,
|
||||
bool use_smbus = false,
|
||||
uint32_t timeout_ms=4) override;
|
||||
|
Loading…
Reference in New Issue
Block a user