mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
f69208d47d
This was previously used to allow to save a state in a SPIDriver so we
could synchronize the initialization of AP_Compass and
AP_InertialSensor.
It was only used by MPU9250 and is not used anymore since the move to
AuxiliaryBus initialization and it's not used anymore since c3dae6f
("AP_InertialSensor: MPU9250: Remove methods not used anymore")
46 lines
1.2 KiB
C++
46 lines
1.2 KiB
C++
|
|
#ifndef __AP_HAL_SPI_DRIVER_H__
|
|
#define __AP_HAL_SPI_DRIVER_H__
|
|
|
|
#include "AP_HAL_Namespace.h"
|
|
|
|
|
|
class AP_HAL::SPIDeviceManager {
|
|
public:
|
|
virtual void init() = 0;
|
|
virtual AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index = 0) = 0;
|
|
};
|
|
|
|
/**
|
|
* We still need an abstraction for performing bulk
|
|
* transfers to be portable to other platforms.
|
|
*/
|
|
|
|
class AP_HAL::SPIDeviceDriver {
|
|
public:
|
|
virtual void init() = 0;
|
|
virtual AP_HAL::Semaphore* get_semaphore() = 0;
|
|
virtual bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len) = 0;
|
|
|
|
virtual void cs_assert() = 0;
|
|
virtual void cs_release() = 0;
|
|
virtual uint8_t transfer (uint8_t data) = 0;
|
|
virtual void transfer (const uint8_t *data, uint16_t len) = 0;
|
|
|
|
/**
|
|
optional set_bus_speed() interface. This can be used by drivers
|
|
to request higher speed for sensor registers once the sensor is
|
|
initialised. This is used by the MPU6000 driver which can
|
|
handle 20MHz for sensor register reads, but only 1MHz for other
|
|
registers.
|
|
*/
|
|
enum bus_speed {
|
|
SPI_SPEED_LOW, SPI_SPEED_HIGH
|
|
};
|
|
|
|
virtual void set_bus_speed(enum bus_speed speed) {}
|
|
};
|
|
|
|
#endif // __AP_HAL_SPI_DRIVER_H__
|
|
|