@ -137,6 +137,14 @@ int I2CBus::open(uint8_t n)
return fd;
}
I2CDevice::I2CDevice(I2CBus &bus, uint8_t address)
: _bus(bus)
, _address(address)
{
set_device_bus(bus.bus);
set_device_address(address);
I2CDevice::~I2CDevice()
// Unregister itself from the I2CDeviceManager
@ -38,11 +38,7 @@ public:
/* AP_HAL::I2CDevice implementation */
I2CDevice(I2CBus &bus, uint8_t address)
I2CDevice(I2CBus &bus, uint8_t address);
~I2CDevice();
@ -212,6 +212,9 @@ SPIDevice::SPIDevice(SPIBus &bus, SPIDesc &device_desc)
, _desc(device_desc)
set_device_bus(_bus.bus);
set_device_address(_desc.subdev);
if (_desc.cs_pin != SPI_CS_KERNEL) {
_cs = hal.gpio->channel(_desc.cs_pin);
if (!_cs) {