2015-12-22 16:22:45 -04:00
|
|
|
#pragma once
|
2013-09-28 11:51:43 -03:00
|
|
|
|
2015-12-22 16:22:45 -04:00
|
|
|
#include <vector>
|
|
|
|
|
|
|
|
#include <AP_HAL/SPIDevice.h>
|
|
|
|
#include <AP_HAL/utility/OwnPtr.h>
|
2013-09-28 11:51:43 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_Linux.h"
|
2013-09-28 11:51:43 -03:00
|
|
|
#include "Semaphores.h"
|
|
|
|
|
2014-08-17 23:32:57 -03:00
|
|
|
#define LINUX_SPI_MAX_BUSES 3
|
|
|
|
|
2014-10-14 21:14:03 -03:00
|
|
|
// Fake CS pin to indicate in-kernel handling
|
|
|
|
#define SPI_CS_KERNEL -1
|
|
|
|
|
2015-12-22 16:22:45 -04:00
|
|
|
namespace Linux {
|
|
|
|
|
|
|
|
class SPIBus;
|
|
|
|
|
|
|
|
class SPIDeviceDriver : public AP_HAL::SPIDeviceDriver {
|
2013-09-28 11:51:43 -03:00
|
|
|
public:
|
2015-12-22 16:22:45 -04:00
|
|
|
friend class SPIDeviceManager;
|
|
|
|
friend class SPIDevice;
|
2015-12-07 21:08:42 -04:00
|
|
|
|
|
|
|
SPIDeviceDriver(const char *name, uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDeviceType type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
|
|
|
|
|
2013-09-28 11:51:43 -03:00
|
|
|
void init();
|
2014-06-27 06:38:32 -03:00
|
|
|
AP_HAL::Semaphore *get_semaphore();
|
2015-08-19 12:36:45 -03:00
|
|
|
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
2013-09-28 11:51:43 -03:00
|
|
|
|
|
|
|
void cs_assert();
|
|
|
|
void cs_release();
|
|
|
|
uint8_t transfer (uint8_t data);
|
|
|
|
void transfer (const uint8_t *data, uint16_t len);
|
2014-07-05 08:14:11 -03:00
|
|
|
void set_bus_speed(enum bus_speed speed);
|
2014-06-27 06:38:32 -03:00
|
|
|
|
2013-09-28 11:51:43 -03:00
|
|
|
private:
|
2014-10-14 21:14:03 -03:00
|
|
|
uint16_t _bus;
|
|
|
|
uint16_t _subdev;
|
|
|
|
int16_t _cs_pin;
|
2014-06-03 05:59:39 -03:00
|
|
|
AP_HAL::DigitalSource *_cs;
|
2015-12-07 21:08:42 -04:00
|
|
|
const char *_name;
|
2013-09-28 11:51:43 -03:00
|
|
|
uint8_t _mode;
|
|
|
|
uint8_t _bitsPerWord;
|
2014-07-05 08:14:11 -03:00
|
|
|
uint32_t _lowspeed;
|
|
|
|
uint32_t _highspeed;
|
2013-09-28 11:51:43 -03:00
|
|
|
uint32_t _speed;
|
2015-12-07 12:19:26 -04:00
|
|
|
enum AP_HAL::SPIDeviceType _type;
|
2016-01-01 10:35:04 -04:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _fake_dev;
|
2013-09-28 11:51:43 -03:00
|
|
|
};
|
|
|
|
|
2015-12-22 16:22:45 -04:00
|
|
|
class SPIDeviceManager : public AP_HAL::SPIDeviceManager {
|
2013-09-28 11:51:43 -03:00
|
|
|
public:
|
2015-12-22 16:22:45 -04:00
|
|
|
friend class SPIDevice;
|
|
|
|
|
|
|
|
static SPIDeviceManager *from(AP_HAL::SPIDeviceManager *spi_mgr)
|
|
|
|
{
|
|
|
|
return static_cast<SPIDeviceManager*>(spi_mgr);
|
|
|
|
}
|
|
|
|
|
|
|
|
SPIDeviceManager()
|
|
|
|
{
|
|
|
|
/* Reserve space up-front for 3 buses */
|
|
|
|
_buses.reserve(3);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name);
|
|
|
|
|
|
|
|
// Temporary function to interoperate with SPIDeviceDriver interface
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(SPIDeviceDriver &desc);
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void init();
|
2015-12-07 12:19:26 -04:00
|
|
|
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDeviceType, uint8_t index = 0);
|
2014-06-27 06:38:32 -03:00
|
|
|
|
2015-12-07 12:19:26 -04:00
|
|
|
static void cs_assert(enum AP_HAL::SPIDeviceType type);
|
|
|
|
static void cs_release(enum AP_HAL::SPIDeviceType type);
|
2015-10-20 18:13:25 -03:00
|
|
|
static bool transaction(SPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
2014-06-27 06:38:32 -03:00
|
|
|
|
2015-12-22 16:19:17 -04:00
|
|
|
protected:
|
2015-12-22 16:22:45 -04:00
|
|
|
void _unregister(SPIBus &b);
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _create_device(SPIBus &b, SPIDeviceDriver &device_desc) const;
|
|
|
|
|
|
|
|
std::vector<SPIBus*> _buses;
|
|
|
|
|
2015-12-22 16:19:17 -04:00
|
|
|
static const uint8_t _n_device_desc;
|
2015-10-20 18:13:25 -03:00
|
|
|
static SPIDeviceDriver _device[];
|
2013-09-28 11:51:43 -03:00
|
|
|
};
|
|
|
|
|
2015-12-22 16:22:45 -04:00
|
|
|
}
|