mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_Linux: export number of SPI devices
Save in the manager the number of devices so it can be used in other places like the SPIDevice implementation. This is a temporary storage while we migrate to SPIDevice. While at it use protected rather than private.
This commit is contained in:
parent
cb40444bf8
commit
0d1bb7aa84
@ -78,6 +78,7 @@ SPIDeviceDriver SPIDeviceManager::_device[0];
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LINUX_SPI_DEVICE_NUM_DEVICES ARRAY_SIZE(SPIDeviceManager::_device)
|
#define LINUX_SPI_DEVICE_NUM_DEVICES ARRAY_SIZE(SPIDeviceManager::_device)
|
||||||
|
const uint8_t SPIDeviceManager::_n_device_desc = LINUX_SPI_DEVICE_NUM_DEVICES;
|
||||||
|
|
||||||
// have a separate semaphore per bus
|
// have a separate semaphore per bus
|
||||||
Semaphore SPIDeviceManager::_semaphore[LINUX_SPI_MAX_BUSES];
|
Semaphore SPIDeviceManager::_semaphore[LINUX_SPI_MAX_BUSES];
|
||||||
|
@ -52,7 +52,8 @@ public:
|
|||||||
static void cs_release(enum AP_HAL::SPIDeviceType type);
|
static void cs_release(enum AP_HAL::SPIDeviceType type);
|
||||||
static bool transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
static bool transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
|
static const uint8_t _n_device_desc;
|
||||||
static SPIDeviceDriver _device[];
|
static SPIDeviceDriver _device[];
|
||||||
static Semaphore _semaphore[LINUX_SPI_MAX_BUSES];
|
static Semaphore _semaphore[LINUX_SPI_MAX_BUSES];
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user