2013-01-12 07:13:04 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2012-12-12 18:01:40 -04:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
|
|
|
|
#include <avr/io.h>
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include "SPIDevices.h"
|
|
|
|
#include "GPIO.h"
|
2013-01-02 06:07:19 -04:00
|
|
|
#include "Semaphores.h"
|
2012-11-28 21:57:20 -04:00
|
|
|
|
2013-05-15 15:00:13 -03:00
|
|
|
#include "utility/pins_arduino_mega.h"
|
2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
using namespace AP_HAL_AVR;
|
|
|
|
|
|
|
|
#define SPI3_MOSI 14
|
|
|
|
#define SPI3_MISO 15
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
AVRSemaphore AVRSPI3DeviceDriver::_semaphore;
|
|
|
|
|
|
|
|
void AVRSPI3DeviceDriver::init() {
|
|
|
|
/* the spi3 (USART3) sck pin PORTJ2 is not enumerated
|
|
|
|
* by the arduino pin numbers, so we access it directly
|
|
|
|
* with AVRDigitalSource. */
|
|
|
|
AVRDigitalSource spi3_sck(_BV(2), PJ);
|
2014-06-01 20:26:19 -03:00
|
|
|
spi3_sck.mode(HAL_GPIO_OUTPUT);
|
|
|
|
hal.gpio->pinMode(SPI3_MOSI, HAL_GPIO_OUTPUT);
|
|
|
|
hal.gpio->pinMode(SPI3_MISO, HAL_GPIO_INPUT);
|
2012-11-28 21:57:20 -04:00
|
|
|
|
|
|
|
/* UMSELn1 and UMSELn2: USART in SPI Master mode */
|
|
|
|
UCSR3C = _BV(UMSEL31) | _BV(UMSEL30);
|
|
|
|
/* Enable RX and TX. */
|
|
|
|
UCSR3B = _BV(RXEN3) | _BV(TXEN3);
|
|
|
|
|
|
|
|
/* Setup chip select pin */
|
2014-06-01 20:26:19 -03:00
|
|
|
_cs_pin->mode(HAL_GPIO_OUTPUT);
|
2012-11-28 21:57:20 -04:00
|
|
|
_cs_pin->write(1);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::Semaphore* AVRSPI3DeviceDriver::get_semaphore() {
|
|
|
|
return &_semaphore;
|
|
|
|
}
|
|
|
|
|
2013-10-11 05:33:47 -03:00
|
|
|
void AVRSPI3DeviceDriver::_cs_assert()
|
|
|
|
{
|
2012-11-28 21:57:20 -04:00
|
|
|
/* set the device UCSRnC configuration bits.
|
|
|
|
* only sets data order, clock phase, and clock polarity bits (lowest
|
|
|
|
* three bits) */
|
2013-10-11 05:33:47 -03:00
|
|
|
const uint8_t new_ucsr3c = (UCSR3C & ~0x07) | (_ucsr3c & (0x07));
|
2012-11-28 21:57:20 -04:00
|
|
|
UCSR3C = new_ucsr3c;
|
|
|
|
/* set the device baud rate */
|
|
|
|
UBRR3 = _ubrr3;
|
|
|
|
|
|
|
|
_cs_pin->write(0);
|
|
|
|
}
|
|
|
|
|
2012-12-17 21:07:06 -04:00
|
|
|
void AVRSPI3DeviceDriver::_cs_release() {
|
2012-11-28 21:57:20 -04:00
|
|
|
_cs_pin->write(1);
|
|
|
|
}
|
|
|
|
|
2012-12-17 21:07:06 -04:00
|
|
|
uint8_t AVRSPI3DeviceDriver::_transfer(uint8_t data) {
|
2012-11-28 21:57:20 -04:00
|
|
|
/* Wait for empty transmit buffer */
|
|
|
|
while ( !( UCSR3A & _BV(UDRE3)) ) ;
|
|
|
|
|
|
|
|
/* Put data into buffer, sends the data */
|
|
|
|
UDR3 = data;
|
|
|
|
|
|
|
|
/* Wait for data to be received */
|
|
|
|
while ( !(UCSR3A & _BV(RXC3)) ) ;
|
|
|
|
|
|
|
|
/* Get and return received data from buffer */
|
|
|
|
return UDR3;
|
|
|
|
}
|
|
|
|
|
2013-01-12 07:13:04 -04:00
|
|
|
void AVRSPI3DeviceDriver::_transfer(const uint8_t *data, uint16_t len) {
|
|
|
|
while (len--) {
|
|
|
|
/* Wait for empty transmit buffer */
|
|
|
|
while ( !( UCSR3A & _BV(UDRE3)) ) ;
|
|
|
|
|
|
|
|
/* Put data into buffer, sends the data */
|
|
|
|
UDR3 = *data++;
|
|
|
|
|
|
|
|
/* Wait for data to be received */
|
|
|
|
while ( !(UCSR3A & _BV(RXC3)) ) ;
|
|
|
|
|
|
|
|
// dummy read of UDR3 to complete
|
|
|
|
UDR3;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2012-12-17 21:07:06 -04:00
|
|
|
void AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
|
|
|
|
uint16_t len) {
|
|
|
|
_cs_assert();
|
2012-12-17 21:59:46 -04:00
|
|
|
if (rx == NULL) {
|
2013-01-12 07:13:04 -04:00
|
|
|
_transfer(tx, len);
|
2012-12-17 21:59:46 -04:00
|
|
|
} else {
|
|
|
|
for (uint16_t i = 0; i < len; i++) {
|
|
|
|
rx[i] = _transfer(tx[i]);
|
|
|
|
}
|
2012-12-17 21:07:06 -04:00
|
|
|
}
|
|
|
|
_cs_release();
|
|
|
|
}
|
|
|
|
|
|
|
|
void AVRSPI3DeviceDriver::cs_assert() {
|
|
|
|
_cs_assert();
|
|
|
|
}
|
|
|
|
|
|
|
|
void AVRSPI3DeviceDriver::cs_release() {
|
|
|
|
_cs_release();
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t AVRSPI3DeviceDriver::transfer(uint8_t data) {
|
|
|
|
return _transfer(data);
|
|
|
|
}
|
|
|
|
|
2013-01-12 07:13:04 -04:00
|
|
|
void AVRSPI3DeviceDriver::transfer(const uint8_t *data, uint16_t len) {
|
|
|
|
_transfer(data, len);
|
|
|
|
}
|
|
|
|
|
2012-12-12 18:01:40 -04:00
|
|
|
#endif
|