mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_Linux: fixed I2C get_device() interface
just stubs for now
This commit is contained in:
parent
5e19183e90
commit
43c1bd0ae9
@ -344,7 +344,10 @@ I2CDeviceManager::get_device(std::vector<const char *> devpaths, uint8_t address
|
||||
}
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
||||
I2CDeviceManager::get_device(uint8_t bus, uint8_t address)
|
||||
I2CDeviceManager::get_device(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) {
|
||||
|
@ -105,7 +105,10 @@ public:
|
||||
std::vector<const char *> devpaths, uint8_t address);
|
||||
|
||||
/* AP_HAL::I2CDeviceManager implementation */
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address) override;
|
||||
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;
|
||||
|
||||
/*
|
||||
* Stop all I2C threads and block until they are finalized. This doesn't
|
||||
|
Loading…
Reference in New Issue
Block a user