mirror of https://github.com/ArduPilot/ardupilot
SPI3: add new library to make use of secondary SPI bus
This commit is contained in:
parent
812ed3d8bf
commit
1cf0b2334a
|
@ -0,0 +1,93 @@
|
||||||
|
/*
|
||||||
|
* SPI3.cpp - SPI library using UART3 for Ardupilot Mega
|
||||||
|
* Code by Randy Mackay, DIYDrones.com
|
||||||
|
* but mostly based on standard Arduino SPI class by Cristian Maglie <c.maglie@bug.st>
|
||||||
|
*
|
||||||
|
* This library is free software; you can redistribute it and/or
|
||||||
|
* modify it under the terms of the GNU Lesser General Public
|
||||||
|
* License as published by the Free Software Foundation; either
|
||||||
|
* version 2.1 of the License, or (at your option) any later version.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "pins_arduino.h"
|
||||||
|
#include "SPI3.h"
|
||||||
|
|
||||||
|
SPI3Class SPI3;
|
||||||
|
bool SPI3Class::_initialised = false;
|
||||||
|
|
||||||
|
void SPI3Class::begin() {
|
||||||
|
|
||||||
|
// check if begin has been run already
|
||||||
|
if( _initialised ) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set direction register for SCK and MOSI pin.
|
||||||
|
pinMode(SPI3_SCK, OUTPUT);
|
||||||
|
pinMode(SPI3_MOSI, OUTPUT);
|
||||||
|
pinMode(SPI3_MISO, INPUT);
|
||||||
|
|
||||||
|
// Setup Serial Port3 in SPI mode (MSPI), Mode 0, Clock: 8Mhz
|
||||||
|
UBRR3 = 0;
|
||||||
|
DDRJ |= (1<<PJ2); // SPI clock XCK3 (PJ2) as output. This enable SPI Master mode
|
||||||
|
|
||||||
|
// put UART3 into SPI master mode, default mode and LSB bit order
|
||||||
|
UCSR3C = SPI3_USART_SPI_MASTER | SPI3_DEFAULT_MODE;
|
||||||
|
|
||||||
|
// Enable receiver and transmitter.
|
||||||
|
UCSR3B = (1<<RXEN3)|(1<<TXEN3);
|
||||||
|
|
||||||
|
// Set Baud rate
|
||||||
|
UBRR3 = SPI3_DEFAULT_SPEED; // SPI running at 2Mhz by default
|
||||||
|
|
||||||
|
// initialisation complete
|
||||||
|
_initialised = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// end - switch UART3 back to asyncronous UART
|
||||||
|
// Note: this is untested
|
||||||
|
void SPI3Class::end() {
|
||||||
|
uint8_t temp = UCSR3C;
|
||||||
|
|
||||||
|
// put UART3 into ASync UART mode
|
||||||
|
temp = (temp & ~SPI3_USART_MASK) | SPI3_USART_ASYNC_UART;
|
||||||
|
UCSR3C = temp;
|
||||||
|
|
||||||
|
// reinitialisation will be required
|
||||||
|
_initialised = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t SPI3Class::transfer(uint8_t data) {
|
||||||
|
/* Wait for empty transmit buffer */
|
||||||
|
while ( !( UCSR3A & (1<<UDRE3)) ) ;
|
||||||
|
|
||||||
|
/* Put data into buffer, sends the data */
|
||||||
|
UDR3 = data;
|
||||||
|
|
||||||
|
/* Wait for data to be received */
|
||||||
|
while ( !(UCSR3A & (1<<RXC3)) ) ;
|
||||||
|
|
||||||
|
/* Get and return received data from buffer */
|
||||||
|
return UDR3;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SPI3Class::setBitOrder(uint8_t bitOrder)
|
||||||
|
{
|
||||||
|
if(bitOrder == SPI3_LSBFIRST) {
|
||||||
|
UCSR3C |= _BV(2);
|
||||||
|
} else {
|
||||||
|
UCSR3C &= ~(_BV(2));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void SPI3Class::setDataMode(uint8_t mode)
|
||||||
|
{
|
||||||
|
UCSR3C = (UCSR3C & ~SPI3_MODE_MASK) | mode;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SPI3Class::setSpeed(uint8_t rate)
|
||||||
|
{
|
||||||
|
UBRR3 = rate;
|
||||||
|
}
|
||||||
|
|
|
@ -0,0 +1,70 @@
|
||||||
|
/*
|
||||||
|
* SPI3.cpp - SPI library using UART3 for Ardupilot Mega
|
||||||
|
* Code by Randy Mackay. DIYDrones.com
|
||||||
|
*
|
||||||
|
* This library is free software; you can redistribute it and/or
|
||||||
|
* modify it under the terms of the GNU Lesser General Public
|
||||||
|
* License as published by the Free Software Foundation; either
|
||||||
|
* version 2.1 of the License, or (at your option) any later version.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _SPI3_H_INCLUDED
|
||||||
|
#define _SPI3_H_INCLUDED
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <avr/pgmspace.h>
|
||||||
|
|
||||||
|
// SPI3's standard pins on Atmega2560
|
||||||
|
#define SPI3_SCK PJ2
|
||||||
|
#define SPI3_MOSI 14
|
||||||
|
#define SPI3_MISO 15
|
||||||
|
|
||||||
|
// used to change UART into SPI mode
|
||||||
|
#define SPI3_USART_MASK 0xC0 // UMSEL31 | UMSEL30
|
||||||
|
#define SPI3_USART_ASYNC_UART 0x00 // UMSEL31 = 0, UMSEL30 = 0
|
||||||
|
#define SPI3_USART_SYNC_UART 0x40 // UMSEL31 = 0, UMSEL30 = 1
|
||||||
|
#define SPI3_USART_SPI_MASTER 0xC0 // UMSEL31 = 1, UMSEL30 = 1
|
||||||
|
|
||||||
|
// spi bus speeds. these assume a 16Mhz clock
|
||||||
|
#define SPI3_SPEED_8MHZ 0x00
|
||||||
|
#define SPI3_SPEED_2MHZ 0x04
|
||||||
|
|
||||||
|
// default speed
|
||||||
|
#define SPI3_DEFAULT_SPEED SPI3_SPEED_2MHZ // 2 megahertz
|
||||||
|
|
||||||
|
// SPI mode definitions
|
||||||
|
#define SPI3_MODE_MASK 0x03
|
||||||
|
#define SPI3_MODE0 0x00
|
||||||
|
#define SPI3_MODE1 0x01
|
||||||
|
#define SPI3_MODE2 0x02
|
||||||
|
#define SPI3_MODE3 0x03
|
||||||
|
#define SPI3_DEFAULT_MODE SPI3_MODE0
|
||||||
|
|
||||||
|
#define SPI3_CLOCK_MASK 0x03 // SPR1 = bit 1, SPR0 = bit 0 on SPCR
|
||||||
|
#define SPI3_2XCLOCK_MASK 0x01 // SPI2X = bit 0 on SPSR
|
||||||
|
|
||||||
|
// SPI bit order
|
||||||
|
#define SPI3_MSBFIRST 0x00
|
||||||
|
#define SPI3_LSBFIRST 0x01
|
||||||
|
|
||||||
|
class SPI3Class {
|
||||||
|
public:
|
||||||
|
|
||||||
|
static void begin();
|
||||||
|
static void end();
|
||||||
|
static uint8_t transfer(byte data);
|
||||||
|
|
||||||
|
// SPI Configuration methods
|
||||||
|
static void setBitOrder(uint8_t bitOrder);
|
||||||
|
static void setDataMode(uint8_t mode);
|
||||||
|
static void setSpeed(uint8_t rate);
|
||||||
|
|
||||||
|
private:
|
||||||
|
static bool _initialised;
|
||||||
|
};
|
||||||
|
|
||||||
|
extern SPI3Class SPI3;
|
||||||
|
|
||||||
|
#endif
|
|
@ -0,0 +1,46 @@
|
||||||
|
/*
|
||||||
|
* Example of AP_OpticalFlow library.
|
||||||
|
* Code by Randy Mackay. DIYDrones.com
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <FastSerial.h>
|
||||||
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
|
#include <SPI3.h> // Arduino SPI library
|
||||||
|
|
||||||
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Serial ports
|
||||||
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
//
|
||||||
|
// Note that FastSerial port buffers are allocated at ::begin time,
|
||||||
|
// so there is not much of a penalty to defining ports that we don't
|
||||||
|
// use.
|
||||||
|
//
|
||||||
|
FastSerialPort0(Serial); // FTDI/console
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
Serial.begin(115200);
|
||||||
|
Serial.println("ArduPilot Mega SPI3 library test ver 0.1");
|
||||||
|
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
// initialise SPI3 bus
|
||||||
|
SPI3.begin();
|
||||||
|
SPI3.setBitOrder(SPI3_MSBFIRST);
|
||||||
|
SPI3.setDataMode(SPI3_MODE0);
|
||||||
|
SPI3.setSpeed(SPI3_SPEED_2MHZ);
|
||||||
|
|
||||||
|
delay(1000);
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
int value;
|
||||||
|
|
||||||
|
// wait for user to enter something
|
||||||
|
while( !Serial.available() ) {
|
||||||
|
value = Serial.read();
|
||||||
|
delay(20);
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,36 @@
|
||||||
|
#######################################
|
||||||
|
# Syntax Coloring Map SPI
|
||||||
|
#######################################
|
||||||
|
|
||||||
|
#######################################
|
||||||
|
# Datatypes (KEYWORD1)
|
||||||
|
#######################################
|
||||||
|
|
||||||
|
SPI3 KEYWORD1
|
||||||
|
|
||||||
|
#######################################
|
||||||
|
# Methods and Functions (KEYWORD2)
|
||||||
|
#######################################
|
||||||
|
begin KEYWORD2
|
||||||
|
end KEYWORD2
|
||||||
|
transfer KEYWORD2
|
||||||
|
setBitOrder KEYWORD2
|
||||||
|
setDataMode KEYWORD2
|
||||||
|
setSpeed KEYWORD2
|
||||||
|
|
||||||
|
|
||||||
|
#######################################
|
||||||
|
# Constants (LITERAL1)
|
||||||
|
#######################################
|
||||||
|
SPI3_CLOCK_DIV4 LITERAL1
|
||||||
|
SPI3_CLOCK_DIV16 LITERAL1
|
||||||
|
SPI3_CLOCK_DIV64 LITERAL1
|
||||||
|
SPI3_CLOCK_DIV128 LITERAL1
|
||||||
|
SPI3_CLOCK_DIV2 LITERAL1
|
||||||
|
SPI3_CLOCK_DIV8 LITERAL1
|
||||||
|
SPI_CLOCK_DIV32 LITERAL1
|
||||||
|
SPI3_CLOCK_DIV64 LITERAL1
|
||||||
|
SPI3_MODE0 LITERAL1
|
||||||
|
SPI3_MODE1 LITERAL1
|
||||||
|
SPI3_MODE2 LITERAL1
|
||||||
|
SPI3_MODE3 LITERAL1
|
Loading…
Reference in New Issue