mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 16:33:58 -04:00
AP_HAL_Linux: add get_device_ptr to HAL I2CDevice API
This commit is contained in:
parent
0a617b500b
commit
07d5938d68
@ -280,11 +280,11 @@ I2CDeviceManager::I2CDeviceManager()
|
||||
_buses.reserve(4);
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
for (uint8_t i = 0, n = _buses.size(); i < n; i++) {
|
||||
if (_buses[i]->bus == bus) {
|
||||
@ -313,10 +313,10 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
|
||||
}
|
||||
|
||||
/* Create a new device increasing the bus reference */
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
||||
AP_HAL::I2CDevice *
|
||||
I2CDeviceManager::_create_device(I2CBus &b, uint8_t address) const
|
||||
{
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(NEW_NOTHROW I2CDevice(b, address));
|
||||
auto *dev = NEW_NOTHROW I2CDevice(b, address);
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -95,10 +95,10 @@ public:
|
||||
I2CDeviceManager();
|
||||
|
||||
/* AP_HAL::I2CDeviceManager implementation */
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address,
|
||||
uint32_t bus_clock=400000,
|
||||
bool use_smbus = false,
|
||||
uint32_t timeout_ms=4) override;
|
||||
AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address,
|
||||
uint32_t bus_clock=400000,
|
||||
bool use_smbus = false,
|
||||
uint32_t timeout_ms=4) override;
|
||||
|
||||
/*
|
||||
* Stop all I2C threads and block until they are finalized. This doesn't
|
||||
@ -124,7 +124,7 @@ public:
|
||||
|
||||
protected:
|
||||
void _unregister(I2CBus &b);
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _create_device(I2CBus &b, uint8_t address) const;
|
||||
AP_HAL::I2CDevice *_create_device(I2CBus &b, uint8_t address) const;
|
||||
|
||||
std::vector<I2CBus*> _buses;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user