mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
HAL_PX4: implement device IDs for I2C and SPI
This commit is contained in:
parent
3d48b6bb3a
commit
16489d2a13
@ -85,6 +85,8 @@ I2CDevice::I2CDevice(uint8_t bus, uint8_t address) :
|
|||||||
_px4dev(_busnum),
|
_px4dev(_busnum),
|
||||||
_address(address)
|
_address(address)
|
||||||
{
|
{
|
||||||
|
set_device_bus(_px4dev.map_bus_number(bus));
|
||||||
|
set_device_address(address);
|
||||||
}
|
}
|
||||||
|
|
||||||
I2CDevice::~I2CDevice()
|
I2CDevice::~I2CDevice()
|
||||||
|
@ -19,9 +19,10 @@ public:
|
|||||||
void set_retries(uint8_t retries) {
|
void set_retries(uint8_t retries) {
|
||||||
_retries = retries;
|
_retries = retries;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint8_t map_bus_number(uint8_t bus) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint8_t map_bus_number(uint8_t bus) const;
|
|
||||||
static uint8_t instance;
|
static uint8_t instance;
|
||||||
bool init_done;
|
bool init_done;
|
||||||
bool init_ok;
|
bool init_ok;
|
||||||
|
@ -64,6 +64,8 @@ SPIDevice::SPIDevice(SPIBus &_bus, SPIDesc &_device_desc)
|
|||||||
: bus(_bus)
|
: bus(_bus)
|
||||||
, device_desc(_device_desc)
|
, device_desc(_device_desc)
|
||||||
{
|
{
|
||||||
|
set_device_bus(_bus.bus);
|
||||||
|
set_device_address(_device_desc.device);
|
||||||
}
|
}
|
||||||
|
|
||||||
SPIDevice::~SPIDevice()
|
SPIDevice::~SPIDevice()
|
||||||
|
Loading…
Reference in New Issue
Block a user