2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_AVR_SPI_DEVICES_H__
|
|
|
|
#define __AP_HAL_AVR_SPI_DEVICES_H__
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2012-11-28 21:57:20 -04:00
|
|
|
#include "AP_HAL_AVR_Namespace.h"
|
|
|
|
|
|
|
|
class AP_HAL_AVR::AVRSPI0DeviceDriver : public AP_HAL::SPIDeviceDriver {
|
|
|
|
public:
|
|
|
|
AVRSPI0DeviceDriver(
|
|
|
|
AP_HAL_AVR::AVRDigitalSource *cs_pin,
|
2013-10-11 04:01:42 -03:00
|
|
|
uint8_t spcr_lowspeed,
|
|
|
|
uint8_t spcr_highspeed,
|
2012-11-28 21:57:20 -04:00
|
|
|
uint8_t spsr
|
|
|
|
) :
|
|
|
|
_cs_pin(cs_pin),
|
2013-10-11 04:01:42 -03:00
|
|
|
_spcr_lowspeed(spcr_lowspeed),
|
|
|
|
_spcr_highspeed(spcr_highspeed),
|
2013-11-16 03:58:32 -04:00
|
|
|
_spcr(spcr_lowspeed),
|
2012-11-28 21:57:20 -04:00
|
|
|
_spsr(spsr)
|
|
|
|
{}
|
|
|
|
|
|
|
|
void init();
|
|
|
|
AP_HAL::Semaphore* get_semaphore();
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2015-08-19 12:39:16 -03:00
|
|
|
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2012-11-28 21:57:20 -04:00
|
|
|
void cs_assert();
|
|
|
|
void cs_release();
|
|
|
|
uint8_t transfer(uint8_t data);
|
2013-01-12 07:13:04 -04:00
|
|
|
void transfer(const uint8_t *data, uint16_t len);
|
2013-10-11 04:01:42 -03:00
|
|
|
void set_bus_speed(enum bus_speed speed);
|
2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
private:
|
2012-12-17 21:07:06 -04:00
|
|
|
void _cs_assert();
|
|
|
|
void _cs_release();
|
|
|
|
uint8_t _transfer(uint8_t data);
|
2013-10-10 07:13:24 -03:00
|
|
|
// used for MPU6k
|
2013-10-28 04:20:20 -03:00
|
|
|
void _transfer16(const uint8_t *tx, uint8_t *rx);
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2012-11-28 21:57:20 -04:00
|
|
|
static AP_HAL_AVR::AVRSemaphore _semaphore;
|
2013-11-15 02:45:02 -04:00
|
|
|
static bool _force_low_speed;
|
2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
AP_HAL_AVR::AVRDigitalSource *_cs_pin;
|
2013-10-11 04:01:42 -03:00
|
|
|
const uint8_t _spcr_lowspeed;
|
|
|
|
const uint8_t _spcr_highspeed;
|
|
|
|
uint8_t _spcr;
|
2012-11-28 21:57:20 -04:00
|
|
|
const uint8_t _spsr;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
class AP_HAL_AVR::AVRSPI2DeviceDriver : public AP_HAL::SPIDeviceDriver {
|
|
|
|
public:
|
|
|
|
AVRSPI2DeviceDriver(
|
|
|
|
AP_HAL_AVR::AVRDigitalSource *cs_pin,
|
|
|
|
uint8_t ucsr2c,
|
|
|
|
uint16_t ubrr2
|
|
|
|
) :
|
|
|
|
_cs_pin(cs_pin),
|
|
|
|
_ucsr2c(ucsr2c),
|
|
|
|
_ubrr2(ubrr2)
|
|
|
|
{}
|
|
|
|
|
|
|
|
void init();
|
|
|
|
AP_HAL::Semaphore* get_semaphore();
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2015-08-19 12:39:16 -03:00
|
|
|
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2012-11-28 21:57:20 -04:00
|
|
|
void cs_assert();
|
|
|
|
void cs_release();
|
|
|
|
uint8_t transfer(uint8_t data);
|
2013-01-12 07:13:04 -04:00
|
|
|
void transfer(const uint8_t *data, uint16_t len);
|
2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
private:
|
2012-12-17 21:07:06 -04:00
|
|
|
void _cs_assert();
|
|
|
|
void _cs_release();
|
|
|
|
uint8_t _transfer(uint8_t data);
|
2013-10-10 07:13:24 -03:00
|
|
|
// used for APM1 ADC
|
|
|
|
void _transfer17(const uint8_t *tx, uint8_t *rx);
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2012-11-28 21:57:20 -04:00
|
|
|
static AP_HAL_AVR::AVRSemaphore _semaphore;
|
|
|
|
|
|
|
|
AP_HAL_AVR::AVRDigitalSource *_cs_pin;
|
|
|
|
uint8_t _ucsr2c;
|
|
|
|
uint16_t _ubrr2;
|
|
|
|
};
|
|
|
|
|
|
|
|
class AP_HAL_AVR::AVRSPI3DeviceDriver : public AP_HAL::SPIDeviceDriver {
|
|
|
|
public:
|
|
|
|
AVRSPI3DeviceDriver(
|
|
|
|
AP_HAL_AVR::AVRDigitalSource *cs_pin,
|
|
|
|
uint8_t ucsr3c,
|
|
|
|
uint16_t ubrr3
|
|
|
|
) :
|
|
|
|
_cs_pin(cs_pin),
|
|
|
|
_ucsr3c(ucsr3c),
|
|
|
|
_ubrr3(ubrr3)
|
|
|
|
{}
|
|
|
|
|
|
|
|
void init();
|
|
|
|
AP_HAL::Semaphore* get_semaphore();
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2015-08-19 12:39:16 -03:00
|
|
|
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
2012-12-17 21:07:06 -04:00
|
|
|
|
2012-11-28 21:57:20 -04:00
|
|
|
void cs_assert();
|
|
|
|
void cs_release();
|
|
|
|
uint8_t transfer(uint8_t data);
|
2013-01-12 07:13:04 -04:00
|
|
|
void transfer(const uint8_t *data, uint16_t len);
|
2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
private:
|
2012-12-17 21:07:06 -04:00
|
|
|
void _cs_assert();
|
|
|
|
void _cs_release();
|
|
|
|
uint8_t _transfer(uint8_t data);
|
2013-01-12 07:13:04 -04:00
|
|
|
void _transfer(const uint8_t *data, uint16_t size);
|
2012-11-28 21:57:20 -04:00
|
|
|
static AP_HAL_AVR::AVRSemaphore _semaphore;
|
|
|
|
|
|
|
|
AP_HAL_AVR::AVRDigitalSource *_cs_pin;
|
|
|
|
uint8_t _ucsr3c;
|
|
|
|
uint16_t _ubrr3;
|
|
|
|
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
#endif // __AP_HAL_AVR_SPI_DEVICES_H__
|