[2.0.x] Add support for LPC1769 at 120 MHz (#9423)

This commit is contained in:
Thomas Moore 2018-02-03 19:33:26 -06:00 committed by Scott Lahteine
parent 6ace57e1b0
commit e1fd9c08b3
19 changed files with 431 additions and 292 deletions

View file

@ -47,113 +47,41 @@
* https://github.com/MarlinFirmware/Marlin/tree/071c7a78f27078fd4aee9a3ef365fcf5e143531e
*/
#include "src/inc/MarlinConfig.h"
#ifdef TARGET_LPC1768
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
//#include "../../../MarlinConfig.h" //works except in U8g
#include "spi_pins.h"
#include "fastio.h"
#include "LPC_SPI.h"
#include "../SPI.h"
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
#if ENABLED(LPC_SOFTWARE_SPI)
// --------------------------------------------------------------------------
// software SPI
// --------------------------------------------------------------------------
/**
* This software SPI runs at three rates. The SD software provides an index
* (spiRate) of 0-6. The mapping is:
* 0-1 - about 5 MHz peak
* 2-3 - about 2 MHz peak
* all others - about 250 KHz
*/
#include "SoftwareSPI.h"
// --------------------------------------------------------------------------
// Software SPI
// --------------------------------------------------------------------------
static uint8_t SPI_speed = 0;
static uint8_t spiTransfer(uint8_t b) {
if (!SPI_speed) { // fastest - about 5 MHz peak
for (int bits = 0; bits < 8; bits++) {
if (b & 0x80) {
WRITE(MOSI_PIN, HIGH);
WRITE(MOSI_PIN, HIGH); // delay to (hopefully) guarantee setup time
}
else {
WRITE(MOSI_PIN, LOW);
WRITE(MOSI_PIN, LOW); // delay to (hopefully) guarantee setup time
}
b <<= 1;
WRITE(SCK_PIN, HIGH);
if (READ(MISO_PIN)) {
b |= 1;
}
WRITE(SCK_PIN, LOW);
}
}
else if (SPI_speed == 1) { // medium - about 1 MHz
for (int bits = 0; bits < 8; bits++) {
if (b & 0x80) {
for (uint8_t i = 0; i < 9; i++) WRITE(MOSI_PIN, HIGH);
}
else {
for (uint8_t i = 0; i < 9; i++) WRITE(MOSI_PIN, LOW);
}
b <<= 1;
for (uint8_t i = 0; i < 7; i++) WRITE(SCK_PIN, HIGH);
if (READ(MISO_PIN)) {
b |= 1;
}
WRITE(SCK_PIN, LOW);
}
}
else { // slow - about 250 KHz
for (int bits = 0; bits < 8; bits++) {
if (b & 0x80) {
WRITE(MOSI_PIN, HIGH);
}
else {
WRITE(MOSI_PIN, LOW);
}
b <<= 1;
delayMicroseconds(1U);
WRITE(SCK_PIN, HIGH);
delayMicroseconds(2U);
if (READ(MISO_PIN)) {
b |= 1;
}
WRITE(SCK_PIN, LOW);
delayMicroseconds(1U);
}
}
return b;
return swSpiTransfer(b, SPI_speed, SCK_PIN, MISO_PIN, MOSI_PIN);
}
void spiBegin() {
SET_OUTPUT(SCK_PIN);
SET_INPUT(MISO_PIN);
SET_OUTPUT(MOSI_PIN);
swSpiBegin(SCK_PIN, MISO_PIN, MOSI_PIN);
}
void spiInit(uint8_t spiRate) {
SPI_speed = spiRate >> 1;
WRITE(MOSI_PIN, HIGH);
WRITE(SCK_PIN, LOW);
SPI_speed = swSpiInit(spiRate, SCK_PIN, MOSI_PIN);
}
uint8_t spiRec() {
@ -193,20 +121,6 @@
WRITE(SS_PIN, HIGH);
}
void SPIClass::begin() { spiBegin(); }
uint8_t SPIClass::transfer(uint8_t B) {
return spiTransfer(B);
}
uint16_t SPIClass::transfer16(uint16_t data) {
uint16_t buffer;
buffer = transfer((data>>8) & 0xFF) << 8;
buffer |= transfer(data & 0xFF) && 0xFF;
return buffer;
}
SPIClass SPI;
#else
// hardware SPI
@ -221,13 +135,13 @@
PinCfg.Funcnum = 2;
PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
PinCfg.Pinnum = LPC1768_PIN_PIN(SCK_PIN);
PinCfg.Portnum = LPC1768_PIN_PORT(SCK_PIN);
PinCfg.Pinnum = LPC1768_PIN_PIN(SCK_PIN);
PinCfg.Portnum = LPC1768_PIN_PORT(SCK_PIN);
PINSEL_ConfigPin(&PinCfg);
SET_OUTPUT(SCK_PIN);
PinCfg.Pinnum = LPC1768_PIN_PIN(MISO_PIN);
PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
PinCfg.Pinnum = LPC1768_PIN_PIN(MISO_PIN);
PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
PINSEL_ConfigPin(&PinCfg);
SET_INPUT(MISO_PIN);
@ -237,10 +151,9 @@ PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
SET_OUTPUT(MOSI_PIN);
}
void spiInit(uint8_t spiRate) {
// table to convert Marlin spiRates (0-5 plus default) into bit rates
// table to convert Marlin spiRates (0-5 plus default) into bit rates
uint32_t Marlin_speed[7]; // CPSR is always 2
Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED
Marlin_speed[1] = 4166667; //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED
@ -250,11 +163,10 @@ PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6
Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h
// select 50MHz PCLK for SSP0
// divide PCLK by 2 for SSP0
CLKPWR_SetPCLKDiv(CLKPWR_PCLKSEL_SSP0, CLKPWR_PCLKSEL_CCLK_DIV_2);
// setup for SPI mode
// setup for SPI mode
SSP_CFG_Type HW_SPI_init; // data structure to hold init values
SSP_ConfigStructInit(&HW_SPI_init); // set values for SPI mode
HW_SPI_init.ClockRate = Marlin_speed[MIN(spiRate, 6)]; // put in the specified bit rate
@ -285,9 +197,8 @@ PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
void spiSend(uint32_t chan, const uint8_t* buf, size_t n) {
}
uint8_t get_one_byte() {
// send a dummy byte so can clock in receive data
static uint8_t get_one_byte() {
// send a dummy byte so can clock in receive data
SSP_SendData(LPC_SSP0,0x00FF);
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
return SSP_ReceiveData(LPC_SSP0) & 0x00FF;
@ -312,6 +223,13 @@ PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
}
}
static uint8_t spiTransfer(uint8_t b) {
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_RXFIFO_NOTEMPTY) || SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)) SSP_ReceiveData(LPC_SSP0); //flush the receive buffer
SSP_SendData(LPC_SSP0, b); // send the byte
while (SSP_GetStatus(LPC_SSP0, SSP_STAT_BUSY)); // wait for it to finish
return SSP_ReceiveData(LPC_SSP0) & 0x00FF;
}
// Write from buffer to SPI
void spiSendBlock(uint8_t token, const uint8_t* buf) {
}
@ -324,5 +242,19 @@ PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
#endif // ENABLED(LPC_SOFTWARE_SPI)
void SPIClass::begin() { spiBegin(); }
uint8_t SPIClass::transfer(uint8_t B) {
return spiTransfer(B);
}
uint16_t SPIClass::transfer16(uint16_t data) {
uint16_t buffer;
buffer = transfer((data>>8) & 0xFF) << 8;
buffer |= transfer(data & 0xFF) && 0xFF;
return buffer;
}
SPIClass SPI;
#endif // TARGET_LPC1768

View file

@ -41,6 +41,8 @@ void HardwareSerial::begin(uint32_t baudrate) {
PINSEL_CFG_Type PinCfg;
UART_FIFO_CFG_Type FIFOConfig;
if (Baudrate == baudrate) return; // No need to re-initialize
if (UARTx == LPC_UART0) {
// Initialize UART0 pin connect
PinCfg.Funcnum = 1;
@ -117,6 +119,9 @@ void HardwareSerial::begin(uint32_t baudrate) {
#if TX_BUFFER_SIZE > 0
TxQueueWritePos = TxQueueReadPos = 0;
#endif
// Save the configured baudrate
Baudrate = baudrate;
}
int HardwareSerial::peek() {

View file

@ -36,6 +36,7 @@ class HardwareSerial : public Stream {
private:
LPC_UART_TypeDef *UARTx;
uint32_t Baudrate;
uint32_t Status;
uint8_t RxBuffer[RX_BUFFER_SIZE];
uint32_t RxQueueWritePos;
@ -49,6 +50,7 @@ private:
public:
HardwareSerial(LPC_UART_TypeDef *UARTx)
: UARTx(UARTx)
, Baudrate(0)
, RxQueueWritePos(0)
, RxQueueReadPos(0)
#if TX_BUFFER_SIZE > 0

View file

@ -166,11 +166,13 @@ void LPC1768_PWM_init(void) {
LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
uint32_t PR = (CLKPWR_GetPCLK(CLKPWR_PCLKSEL_PWM1) / 1000000) - 1; // Prescalar to create 1 MHz output
LPC_PWM1->MR0 = LPC_PWM1_MR0; // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
// MR0 must be set before TCR enables the PWM
LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST) | _BV(SBIT_PWMEN); // Enable counters, reset counters, set mode to PWM
CBI(LPC_PWM1->TCR, SBIT_CNTRST); // Take counters out of reset
LPC_PWM1->PR = LPC_PWM1_PR;
LPC_PWM1->PR = PR;
LPC_PWM1->MCR = _BV(SBIT_PWMMR0R) | _BV(0); // Reset TC if it matches MR0, disable all interrupts except for MR0
LPC_PWM1->CTCR = 0; // Disable counter mode (enable PWM mode)
LPC_PWM1->LER = 0x07F; // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
@ -179,7 +181,7 @@ void LPC1768_PWM_init(void) {
//// interrupt controlled PWM setup
LPC_SC->PCONP |= 1 << 23; // power on timer3
HAL_PWM_TIMER->PR = LPC_PWM1_PR;
HAL_PWM_TIMER->PR = PR;
HAL_PWM_TIMER->MCR = 0x0B; // Interrupt on MR0 & MR1, reset on MR0
HAL_PWM_TIMER->MR0 = LPC_PWM1_MR0;
HAL_PWM_TIMER->MR1 = 0;

View file

@ -64,12 +64,11 @@
#define _LPC1768_PWM_H_
#include "pinmapping.h"
#include <lpc17xx_clkpwr.h>
#define LPC_PWM1_MR0 19999 // base repetition rate minus one count - 20mS
#define LPC_PWM1_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output
#define LPC_PWM1_PCLKSEL0 0x00 // select clock source for prescaler - defaults to 25MHz on power up
// 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to PWM1 prescaler
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
#define LPC_PWM1_PCLKSEL0 CLKPWR_PCLKSEL_CCLK_DIV_4 // select clock divider for prescaler - defaults to 4 on power up
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
void LPC1768_PWM_init(void);
bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min=1, uint32_t max=(LPC_PWM1_MR0 - (MR0_MARGIN)), uint8_t servo_index=0xFF);

View file

@ -23,7 +23,7 @@
#ifdef TARGET_LPC1768
#include <stdint.h>
#define MSBFIRST 0
#define MSBFIRST 1
#define SPI_MODE3 0
class SPISettings {

View file

@ -0,0 +1,116 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* Software SPI functions originally from Arduino Sd2Card Library
* Copyright (C) 2009 by William Greiman
*/
/**
*
* For TARGET_LPC1768
*/
#include "src/inc/MarlinConfig.h"
#ifdef TARGET_LPC1768
// --------------------------------------------------------------------------
// Software SPI
// --------------------------------------------------------------------------
/**
* This software SPI runs at multiple rates. The SD software provides an index
* (spiRate) of 0-6. The mapping is:
* 0 - about 5 MHz peak (6 MHz on LPC1769)
* 1-2 - about 2 MHz peak
* 3 - about 1 MHz peak
* 4 - about 500 kHz peak
* 5 - about 250 kHz peak
* 6 - about 125 kHz peak
*/
uint8_t swSpiTransfer(uint8_t b, uint8_t spi_speed, pin_t sck_pin, pin_t miso_pin, pin_t mosi_pin) {
for (uint8_t i = 0; i < 8; i++) {
if (spi_speed == 0) {
if (b & 0x80)
WRITE(mosi_pin, HIGH);
else
WRITE(mosi_pin, LOW);
WRITE(sck_pin, HIGH);
b <<= 1;
if (miso_pin >= 0)
if (READ(miso_pin)) b |= 1;
WRITE(sck_pin, LOW);
}
else {
if (b & 0x80)
for (uint8_t j = 0; j < spi_speed; j++)
WRITE(mosi_pin, HIGH);
else
for (uint8_t j = 0; j < spi_speed; j++)
WRITE(mosi_pin, LOW);
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
WRITE(sck_pin, HIGH);
b <<= 1;
if (miso_pin >= 0)
if (READ(miso_pin)) b |= 1;
for (uint8_t j = 0; j < spi_speed; j++)
WRITE(sck_pin, LOW);
}
}
return b;
}
void swSpiBegin(pin_t sck_pin, pin_t miso_pin, pin_t mosi_pin) {
SET_OUTPUT(sck_pin);
if (VALID_PIN(miso_pin))
SET_INPUT(miso_pin);
SET_OUTPUT(mosi_pin);
}
uint8_t swSpiInit(uint8_t spiRate, pin_t sck_pin, pin_t mosi_pin) {
uint8_t spi_speed = 0;
spiRate = MIN(spiRate, 6);
if (SystemCoreClock == 120000000)
spi_speed = 44 / POW(2, 6 - spiRate);
else
spi_speed = 38 / POW(2, 6 - spiRate);
WRITE(mosi_pin, HIGH);
WRITE(sck_pin, LOW);
return spi_speed;
}
#endif // TARGET_LPC1768

View file

@ -0,0 +1,50 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _SOFTWARE_SPI_H_
#define _SOFTWARE_SPI_H_
#include "pinmapping.h"
// --------------------------------------------------------------------------
// software SPI
// --------------------------------------------------------------------------
/**
* This software SPI runs at multiple rates. The SD software provides an index
* (spiRate) of 0-6. The mapping is:
* 0 - about 5 MHz peak (6 MHz on LPC1769)
* 1-2 - about 2 MHz peak
* 3 - about 1 MHz peak
* 4 - about 500 kHz peak
* 5 - about 250 kHz peak
* 6 - about 125 kHz peak
*/
void swSpiBegin(pin_t sck_pin, pin_t miso_pin, pin_t mosi_pin);
// Returns the spi_speed value to be passed to swSpiTransfer
uint8_t swSpiInit(uint8_t spiRate, pin_t sck_pin, pin_t mosi_pin);
uint8_t swSpiTransfer(uint8_t b, uint8_t spi_speed, pin_t sck_pin, pin_t miso_pin, pin_t mosi_pin);
#endif // _SOFTWARE_SPI_H_

View file

@ -70,6 +70,20 @@ extern "C" void SystemPostInit() {
}
}
// detect 17x[4-8] (100MHz) or 17x9 (120MHz)
static bool isLPC1769() {
#define IAP_LOCATION 0x1FFF1FF1
uint32_t command[1];
uint32_t result[5];
typedef void (*IAP)(uint32_t*, uint32_t*);
IAP iap = (IAP) IAP_LOCATION;
command[0] = 54;
iap(command, result);
return ((result[1] & 0x00100000) != 0);
}
extern uint32_t MSC_SD_Init(uint8_t pdrv);
int main(void) {
@ -93,7 +107,7 @@ int main(void) {
#if NUM_SERIAL > 1
MYSERIAL1.begin(BAUDRATE);
#endif
SERIAL_PRINTF("\n\nLPC1768 (%dMhz) UART0 Initialised\n", SystemCoreClock / 1000000);
SERIAL_PRINTF("\n\n%s (%dMhz) UART0 Initialised\n", isLPC1769() ? "LPC1769" : "LPC1768", SystemCoreClock / 1000000);
SERIAL_FLUSHTX();
#endif

View file

@ -143,8 +143,10 @@ constexpr int8_t LPC1768_PIN_ADC(const pin_t pin) { return (int8_t)((pin >> 10)
#define P0_26 LPC1768_PIN(PORT(0), PIN(26), INTERRUPT(1), PWM(0), ADC_CHAN(3))
#define P0_27 LPC1768_PIN(PORT(0), PIN(27), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_28 LPC1768_PIN(PORT(0), PIN(28), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_29 LPC1768_PIN(PORT(0), PIN(29), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_30 LPC1768_PIN(PORT(0), PIN(30), INTERRUPT(1), PWM(0), ADC_NONE)
#if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
#define P0_29 LPC1768_PIN(PORT(0), PIN(29), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_30 LPC1768_PIN(PORT(0), PIN(30), INTERRUPT(1), PWM(0), ADC_NONE)
#endif
#define P1_00 LPC1768_PIN(PORT(1), PIN( 0), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_01 LPC1768_PIN(PORT(1), PIN( 1), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_04 LPC1768_PIN(PORT(1), PIN( 4), INTERRUPT(0), PWM(0), ADC_NONE)
@ -216,7 +218,13 @@ constexpr pin_t pin_map[] = {
P_NC,
#endif
P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23,
P0_24, P0_25, P0_26, P0_27, P0_28, P0_29, P0_30, P_NC,
P0_24, P0_25, P0_26, P0_27, P0_28,
#if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
P0_29, P0_30,
#else
P_NC, P_NC,
#endif
P_NC,
P1_00, P1_01, P_NC, P_NC, P1_04, P_NC, P_NC, P_NC,
P1_08, P1_09, P1_10, P_NC, P_NC, P_NC, P1_14, P1_15,
@ -248,15 +256,14 @@ constexpr pin_t adc_pin_table[] = {
#endif
};
#if SERIAL_PORT != 0
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
#define NUM_ANALOG_INPUTS 8
#else
#define NUM_ANALOG_INPUTS 6
#endif
// P0.6 thru P0.9 are for the onboard SD card
// P0.29 and P0.30 are for the USB port
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, P0_29, P0_30
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
// Get the digital pin for an analog index
pin_t analogInputToDigitalPin(const int8_t p);

View file

@ -23,10 +23,14 @@
#ifndef SPI_PINS_LPC1768_H
#define SPI_PINS_LPC1768_H
#define LPC_SOFTWARE_SPI // Re-ARM board needs a software SPI because using the
// standard LCD adapter results in the LCD and the
// SD card sharing a single SPI when the RepRap Full
// Graphic Smart Controller is selected
#include "src/core/macros.h"
#if ENABLED(SDSUPPORT) && ENABLED(DOGLCD) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
#define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently
// needed due to the speed and mode requred for communicating with each device being different.
// This requirement can be removed if the SPI access to these devices is updated to use
// spiBeginTransaction.
#endif
/** onboard SD card */
//#define SCK_PIN P0_07

View file

@ -58,52 +58,12 @@
#ifdef TARGET_LPC1768
#include <U8glib.h>
#include "SoftwareSPI.h"
#include <lpc17xx_pinsel.h>
#define LPC_PORT_OFFSET (0x0020)
#define LPC_PIN(pin) (1UL << pin)
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
uint8_t SCK_pin_ST7920_HAL, SCK_port_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL, MOSI_port_ST7920_HAL;
#define SPI_SPEED 4 //20: 200KHz 5:750KHz 4:1MHz 3:1.5MHz 2:3-4MHz
static void spiSend_sw(uint8_t val)
{
for (uint8_t i = 0; i < 8; i++) {
if (val & 0x80)
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOSET = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOSET = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOSET = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
}
else
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOCLR = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOCLR = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOCLR = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port_ST7920_HAL)->FIOCLR = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOCLR = LPC_PIN(SCK_pin_ST7920_HAL);
}
val = val << 1;
}
}
#define SPI_SPEED 3 // About 1 MHz
static pin_t SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL;
static uint8_t SPI_speed = 0;
static uint8_t rs_last_state = 255;
static void u8g_com_LPC1768_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val)
@ -115,39 +75,38 @@
if ( rs == 0 )
/* command */
spiSend_sw(0x0f8);
swSpiTransfer(0x0f8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
else
/* data */
spiSend_sw(0x0fa);
swSpiTransfer(0x0fa, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
for( i = 0; i < 4; i++ ) // give the controller some time to process the data
u8g_10MicroDelay(); // 2 is bad, 3 is OK, 4 is safe
}
spiSend_sw(val & 0x0f0);
spiSend_sw(val << 4);
swSpiTransfer(val & 0x0f0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
swSpiTransfer(val << 4, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
}
uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_INIT:
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
SCK_pin_ST7920_HAL = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_SCK]);
SCK_port_ST7920_HAL = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_SCK]);
MOSI_pin_ST7920_HAL_HAL = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_MOSI]);
MOSI_port_ST7920_HAL = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_MOSI]);
SCK_pin_ST7920_HAL = u8g->pin_list[U8G_PI_SCK];
MOSI_pin_ST7920_HAL_HAL = u8g->pin_list[U8G_PI_MOSI];
u8g_SetPILevel(u8g, U8G_PI_CS, 0);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_SetPILevel(u8g, U8G_PI_SCK, 0);
u8g_SetPIOutput(u8g, U8G_PI_SCK);
u8g_SetPILevel(u8g, U8G_PI_MOSI, 0);
u8g_SetPIOutput(u8g, U8G_PI_MOSI);
u8g_Delay(5);
SPI_speed = swSpiInit(SPI_SPEED, SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL);
u8g_SetPILevel(u8g, U8G_PI_CS, 0);
u8g_SetPILevel(u8g, U8G_PI_SCK, 0);
u8g_SetPILevel(u8g, U8G_PI_MOSI, 0);
u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: command mode */
break;

View file

@ -55,95 +55,44 @@
*/
#if defined (TARGET_LPC1768)
#include <U8glib.h>
#include "SoftwareSPI.h"
#include <lpc17xx_pinsel.h>
#define SPI_SPEED 2 // About 2 MHz
#define LPC_PORT_OFFSET (0x0020)
#define LPC_PIN(pin) (1UL << pin)
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
void delayMicroseconds(uint32_t us);
void pinMode(int16_t pin, uint8_t mode);
void digitalWrite(int16_t pin, uint8_t pin_status);
uint8_t SCK_pin, SCK_port, MOSI_pin, MOSI_port;
#define SPI_SPEED 2 //20: 200KHz 5:750KHz 2:3-4MHz
static uint8_t SPI_speed = 0;
static void u8g_sw_spi_HAL_LPC1768_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val)
{
for (uint8_t i = 0; i < 8; i++) {
if (val & 0x80)
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port)->FIOSET = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOSET = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOSET = LPC_PIN(MOSI_pin);
}
else
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port)->FIOCLR = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOCLR = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOCLR = LPC_PIN(MOSI_pin);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port)->FIOCLR = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOCLR = LPC_PIN(SCK_pin);
}
val = val << 1;
}
swSpiTransfer(val, SPI_speed, clockPin, -1, dataPin);
}
uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_INIT:
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
SCK_pin = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_SCK]);
SCK_port = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_SCK]);
MOSI_pin = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_MOSI]);
MOSI_port = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_MOSI]);
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
#define OUPUT 0x1
pinMode(u8g->pin_list[U8G_PI_SCK], OUPUT);
pinMode(u8g->pin_list[U8G_PI_MOSI], OUPUT);
pinMode(u8g->pin_list[U8G_PI_CS], OUPUT);
pinMode(u8g->pin_list[U8G_PI_A0], OUPUT);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) pinMode(u8g->pin_list[U8G_PI_RESET], OUPUT);
digitalWrite(u8g->pin_list[U8G_PI_SCK], 0);
digitalWrite(u8g->pin_list[U8G_PI_MOSI], 0);
u8g_SetPIOutput(u8g, U8G_PI_SCK);
u8g_SetPIOutput(u8g, U8G_PI_MOSI);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_SetPIOutput(u8g, U8G_PI_A0);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPIOutput(u8g, U8G_PI_RESET);
SPI_speed = swSpiInit(SPI_SPEED, u8g->pin_list[U8G_PI_SCK], u8g->pin_list[U8G_PI_MOSI]);
u8g_SetPILevel(u8g, U8G_PI_SCK, 0);
u8g_SetPILevel(u8g, U8G_PI_MOSI, 0);
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
digitalWrite(u8g->pin_list[U8G_PI_RESET], arg_val);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_CHIP_SELECT:
digitalWrite(u8g->pin_list[U8G_PI_CS], !arg_val);
u8g_SetPILevel(u8g, U8G_PI_CS, !arg_val);
break;
case U8G_COM_MSG_WRITE_BYTE:
@ -170,7 +119,7 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val,
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
digitalWrite(u8g->pin_list[U8G_PI_A0], arg_val);
u8g_SetPILevel(u8g, U8G_PI_A0, arg_val);
break;
}
return 1;

View file

@ -436,16 +436,32 @@ void _tmc_say_sgt(const char name[], const uint32_t sgt) {
tmc_status(stepperE0, TMC_E0, i, planner.axis_steps_per_mm[E_AXIS]);
#endif
#if E1_IS_TRINAMIC
tmc_status(stepperE1, TMC_E1, i, planner.axis_steps_per_mm[E_AXIS+1]);
tmc_status(stepperE1, TMC_E1, i, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 1
#endif
]);
#endif
#if E2_IS_TRINAMIC
tmc_status(stepperE2, TMC_E2, i, planner.axis_steps_per_mm[E_AXIS+2]);
tmc_status(stepperE2, TMC_E2, i, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 2
#endif
]);
#endif
#if E3_IS_TRINAMIC
tmc_status(stepperE3, TMC_E3, i, planner.axis_steps_per_mm[E_AXIS+3]);
tmc_status(stepperE3, TMC_E3, i, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 3
#endif
]);
#endif
#if E4_IS_TRINAMIC
tmc_status(stepperE4, TMC_E4, i, planner.axis_steps_per_mm[E_AXIS+4]);
tmc_status(stepperE4, TMC_E4, i, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 4
#endif
]);
#endif
SERIAL_EOL();

View file

@ -29,10 +29,10 @@ class U8GLIB_64128N_2X_HAL : public U8GLIB
{
public:
U8GLIB_64128N_2X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE)
: U8GLIB(&u8g_dev_st7565_64128n_HAL_2x_sw_spi, sck, mosi, cs, a0, reset)
: U8GLIB(&u8g_dev_st7565_64128n_HAL_2x_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset)
{ }
U8GLIB_64128N_2X_HAL(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE)
: U8GLIB(&u8g_dev_st7565_64128n_HAL_2x_hw_spi, cs, a0, reset)
: U8GLIB(&u8g_dev_st7565_64128n_HAL_2x_hw_spi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset)
{ }
};
@ -43,10 +43,10 @@ class U8GLIB_ST7920_128X64_4X_HAL : public U8GLIB
{
public:
U8GLIB_ST7920_128X64_4X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE)
: U8GLIB(&u8g_dev_st7920_128x64_HAL_4x_sw_spi, sck, mosi, cs, U8G_PIN_NONE, reset) // a0 = U8G_PIN_NONE
: U8GLIB(&u8g_dev_st7920_128x64_HAL_4x_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset) // a0 = U8G_PIN_NONE
{ }
U8GLIB_ST7920_128X64_4X_HAL(pin_t cs, pin_t reset = U8G_PIN_NONE)
: U8GLIB(&u8g_dev_st7920_128x64_HAL_4x_hw_spi, cs, U8G_PIN_NONE, reset) // a0 = U8G_PIN_NONE
: U8GLIB(&u8g_dev_st7920_128x64_HAL_4x_hw_spi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset) // a0 = U8G_PIN_NONE
{ }
};
@ -57,7 +57,7 @@ class U8GLIB_ST7920_128X64_RRD : public U8GLIB
{
public:
U8GLIB_ST7920_128X64_RRD(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE)
: U8GLIB(&u8g_dev_st7920_128x64_rrd_sw_spi, sck, mosi, cs, U8G_PIN_NONE, reset) // a0 = U8G_PIN_NONE
: U8GLIB(&u8g_dev_st7920_128x64_rrd_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset) // a0 = U8G_PIN_NONE
{ }
};

View file

@ -160,19 +160,22 @@
// LCD selection
#if ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#ifdef CPU_32_BIT
U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); // Original u8glib device. 2 stripes, SW SPI
#else
#ifdef DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN) && (LCD_PINS_ENABLE == MOSI_PIN)
U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_RS); // 2 stripes, HW SPI (shared with SD card)
#else
U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); // Original u8glib device. 2 stripes, SW SPI
#endif
#elif ENABLED(U8GLIB_ST7920)
// RepRap Discount Full Graphics Smart Controller
//U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_RS); // 2 stripes, HW SPI (shared with SD card, on AVR does not use standard LCD adapter)
#if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN) && (LCD_PINS_ENABLE == MOSI_PIN)
U8GLIB_ST7920_128X64_4X_HAL u8g(LCD_PINS_RS); // 2 stripes, HW SPI (shared with SD card, on AVR does not use standard LCD adapter)
#else
//U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); // Original u8glib device. 2 stripes, SW SPI
U8GLIB_ST7920_128X64_RRD u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); // Number of stripes can be adjusted in ultralcd_st7920_u8glib_rrd.h with PAGE_HEIGHT
// AVR version ignores these pin settings
// HAL version uses these pin settings
#endif
#elif ENABLED(CARTESIO_UI)
// The CartesioUI display
@ -186,8 +189,11 @@
#elif ENABLED(U8GLIB_ST7565_64128N)
// The MaKrPanel, Mini Viki, and Viki 2.0, ST7565 controller
//U8GLIB_64128N_2X_HAL u8g(DOGLCD_CS, DOGLCD_A0); // using HW-SPI
#if DISABLED(SDSUPPORT) && (DOGLCD_SCK == SCK_PIN) && (DOGLCD_MOSI == MOSI_PIN)
U8GLIB_64128N_2X_HAL u8g(DOGLCD_CS, DOGLCD_A0); // using HW-SPI
#else
U8GLIB_64128N_2X_HAL u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0); // using SW-SPI
#endif
#elif ENABLED(MKS_12864OLED_SSD1306)
// MKS 128x64 (SSD1306) OLED I2C LCD

View file

@ -235,16 +235,32 @@
_TMC2130_INIT(E0, planner.axis_steps_per_mm[E_AXIS]);
#endif
#if ENABLED(E1_IS_TMC2130)
{ constexpr int extruder = 1; _TMC2130_INIT(E1, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2130_INIT(E1, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 1
#endif
]);
#endif
#if ENABLED(E2_IS_TMC2130)
{ constexpr int extruder = 2; _TMC2130_INIT(E2, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2130_INIT(E2, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 2
#endif
]);
#endif
#if ENABLED(E3_IS_TMC2130)
{ constexpr int extruder = 3; _TMC2130_INIT(E3, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2130_INIT(E3, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 3
#endif
]);
#endif
#if ENABLED(E4_IS_TMC2130)
{ constexpr int extruder = 4; _TMC2130_INIT(E4, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2130_INIT(E4, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 4
#endif
]);
#endif
}
@ -440,16 +456,32 @@
_TMC2208_INIT(E0, planner.axis_steps_per_mm[E_AXIS]);
#endif
#if ENABLED(E1_IS_TMC2208)
{ constexpr int extruder = 1; _TMC2208_INIT(E1, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2208_INIT(E1, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 1
#endif
]);
#endif
#if ENABLED(E2_IS_TMC2208)
{ constexpr int extruder = 2; _TMC2208_INIT(E2, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2208_INIT(E2, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 2
#endif
]);
#endif
#if ENABLED(E3_IS_TMC2208)
{ constexpr int extruder = 3; _TMC2208_INIT(E3, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2208_INIT(E3, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 3
#endif
]);
#endif
#if ENABLED(E4_IS_TMC2208)
{ constexpr int extruder = 4; _TMC2208_INIT(E4, planner.axis_steps_per_mm[E_AXIS_N]); }
_TMC2208_INIT(E4, planner.axis_steps_per_mm[E_AXIS
#if ENABLED(DISTINCT_E_FACTORS)
+ 4
#endif
]);
#endif
}
#endif // HAVE_TMC2208

View file

@ -496,7 +496,20 @@ void SystemCoreClockUpdate (void) /* Get Core Clock Frequency */
break;
}
}
}
// detect 17x[4-8] (100MHz) or 17x9 (120MHz)
static int can_120MHz() {
#define IAP_LOCATION 0x1FFF1FF1
uint32_t command[1];
uint32_t result[5];
typedef void (*IAP)(uint32_t*, uint32_t*);
IAP iap = (IAP) IAP_LOCATION;
command[0] = 54;
iap(command, result);
return result[1] & 0x00100000;
}
/**
@ -508,7 +521,6 @@ void SystemCoreClockUpdate (void) /* Get Core Clock Frequency */
* @brief Setup the microcontroller system.
* Initialize the System.
*/
void SystemInit (void)
{
#if (CLOCK_SETUP) /* Clock Setup */
@ -546,9 +558,15 @@ void SystemInit (void)
LPC_SC->CCLKCFG = 0x00000002; /* Setup CPU Clock Divider */
LPC_SC->PLL0CFG = 0x00010018; // 100MHz
LPC_SC->PLL0FEED = 0xAA;
LPC_SC->PLL0FEED = 0x55;
if(can_120MHz()) {
LPC_SC->PLL0CFG = 0x0000000E; /* configure PLL0 */
LPC_SC->PLL0FEED = 0xAA;
LPC_SC->PLL0FEED = 0x55;
} else {
LPC_SC->PLL0CFG = 0x00010018; // 100MHz
LPC_SC->PLL0FEED = 0xAA;
LPC_SC->PLL0FEED = 0x55;
}
LPC_SC->PLL0CON = 0x01; /* PLL0 Enable */
LPC_SC->PLL0FEED = 0xAA;

View file

@ -11,10 +11,12 @@
/
/-------------------------------------------------------------------------*/
#include "lpc17xx_ssp.h"
#include "lpc17xx_clkpwr.h"
#include "LPC176x.h"
#define SSP_CH 1 /* SSP channel to use (0:SSP0, 1:SSP1) */
#define CCLK 100000000UL /* cclk frequency [Hz] */
#define PCLK_SSP 50000000UL /* PCLK frequency to be supplied for SSP [Hz] */
#define SCLK_FAST 25000000UL /* SCLK frequency under normal operation [Hz] */
#define SCLK_SLOW 400000UL /* SCLK frequency under initialization [Hz] */
@ -55,21 +57,49 @@
}
#endif
#if PCLK_SSP * 1 == CCLK
#define PCLKDIV_SSP PCLKDIV_1
#elif PCLK_SSP * 2 == CCLK
#define PCLKDIV_SSP PCLKDIV_2
#elif PCLK_SSP * 4 == CCLK
#define PCLKDIV_SSP PCLKDIV_4
#elif PCLK_SSP * 8 == CCLK
#define PCLKDIV_SSP PCLKDIV_8
#else
#error Invalid CCLK:PCLK_SSP combination.
#endif
static void set_spi_clock(uint32_t target_clock)
{
uint32_t prescale, cr0_div, cmp_clk, ssp_clk;
/* The SSP clock is derived from the (main system oscillator / 2),
so compute the best divider from that clock */
#if SSP_CH == 0
ssp_clk = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SSP0);
#elif SSP_CH == 1
ssp_clk = CLKPWR_GetPCLK (CLKPWR_PCLKSEL_SSP1);
#endif
/* Find closest divider to get at or under the target frequency.
Use smallest prescale possible and rely on the divider to get
the closest target frequency */
cr0_div = 0;
cmp_clk = 0xFFFFFFFF;
prescale = 2;
while (cmp_clk > target_clock)
{
cmp_clk = ssp_clk / ((cr0_div + 1) * prescale);
if (cmp_clk > target_clock)
{
cr0_div++;
if (cr0_div > 0xFF)
{
cr0_div = 0;
prescale += 2;
}
}
}
/* Write computed prescaler and divider back to register */
SSPxCR0 &= (~SSP_CR0_SCR(0xFF)) & SSP_CR0_BITMASK;
SSPxCR0 |= (SSP_CR0_SCR(cr0_div)) & SSP_CR0_BITMASK;
SSPxCPSR = prescale & SSP_CPSR_BITMASK;
}
#define FCLK_FAST() { SSPxCR0 = (SSPxCR0 & 0x00FF) | ((PCLK_SSP / 2 / SCLK_FAST) - 1) << 8; }
#define FCLK_SLOW() { SSPxCR0 = (SSPxCR0 & 0x00FF) | ((PCLK_SSP / 2 / SCLK_SLOW) - 1) << 8; }
#define FCLK_FAST() set_spi_clock(SCLK_FAST)
#define FCLK_SLOW() set_spi_clock(SCLK_SLOW)
@ -79,7 +109,6 @@
---------------------------------------------------------------------------*/
#include "LPC176x.h"
#include "diskio.h"
@ -276,7 +305,6 @@ void power_on (void) /* Enable SSP module and attach it to I/O pads */
{
__set_PCONP(PCSSPx, 1); /* Enable SSP module */
__set_PCLKSEL(PCLKSSPx, PCLKDIV_SSP); /* Select PCLK frequency for SSP */
SSPxCPSR = 2; /* CPSDVSR=2 */
SSPxCR0 = 0x0007; /* Set mode: SPI mode 0, 8-bit */
SSPxCR1 = 0x2; /* Enable SSP with Master */
ATTACH_SSP(); /* Attach SSP module to I/O pads */