mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_PX4: fixed I2C get_device() interface
just stubs for now
This commit is contained in:
parent
43c1bd0ae9
commit
ded22a6766
@ -180,7 +180,10 @@ bool I2CDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint3
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(bus, address));
|
||||
return dev;
|
||||
|
@ -90,7 +90,10 @@ public:
|
||||
return static_cast<I2CDeviceManager*>(i2c_mgr);
|
||||
}
|
||||
|
||||
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;
|
||||
};
|
||||
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user