Merge pull request #7770 from thinkyhead/bf2_HAL_cleanups_etc

Some HAL formatting cleanup
This commit is contained in:
Scott Lahteine 2017-09-27 11:11:12 -05:00 committed by GitHub
commit baf0bd2b24
52 changed files with 636 additions and 1020 deletions

View file

@ -4,7 +4,7 @@
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
This program is free software: you can redistribute it and/or modify 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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or

View file

@ -83,7 +83,7 @@
//void cli(void); //void cli(void);
//void _delay_ms(int delay); //void _delay_ms(const int delay);
inline void HAL_clear_reset_source(void) { MCUSR = 0; } inline void HAL_clear_reset_source(void) { MCUSR = 0; }
inline uint8_t HAL_get_reset_source(void) { return MCUSR; } inline uint8_t HAL_get_reset_source(void) { return MCUSR; }

View file

@ -24,7 +24,7 @@
* Originally from Arduino Sd2Card Library * Originally from Arduino Sd2Card Library
* Copyright (C) 2009 by William Greiman * Copyright (C) 2009 by William Greiman
*/ */
/** /**
* Description: HAL for AVR - SPI functions * Description: HAL for AVR - SPI functions
* *

View file

@ -393,7 +393,7 @@ static void pwm_details(uint8_t pin) {
SERIAL_PROTOCOL_SP(10); SERIAL_PROTOCOL_SP(10);
#endif #endif
} }
#define PRINT_PORT(p) print_port(p) #define PRINT_PORT(p) print_port(p)
#endif #endif

View file

@ -1,9 +1,9 @@
/* ************************************************************************** /* **************************************************************************
Marlin 3D Printer Firmware Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
This program is free software: you can redistribute it and/or modify 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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
@ -93,7 +93,7 @@ uint8_t HAL_get_reset_source (void) {
} }
} }
void _delay_ms(int delay_ms) { void _delay_ms(const int delay_ms) {
// todo: port for Due? // todo: port for Due?
delay(delay_ms); delay(delay_ms);
} }
@ -112,7 +112,7 @@ int freeMemory() {
// ADC // ADC
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
void HAL_adc_start_conversion(uint8_t adc_pin) { void HAL_adc_start_conversion(const uint8_t adc_pin) {
HAL_adc_result = analogRead(adc_pin); HAL_adc_result = analogRead(adc_pin);
} }

View file

@ -120,7 +120,7 @@ void HAL_clear_reset_source (void);
/** reset reason */ /** reset reason */
uint8_t HAL_get_reset_source (void); uint8_t HAL_get_reset_source (void);
void _delay_ms(int delay); void _delay_ms(const int delay);
int freeMemory(void); int freeMemory(void);
@ -150,7 +150,7 @@ inline void HAL_adc_init(void) {}//todo
#define HAL_READ_ADC HAL_adc_result #define HAL_READ_ADC HAL_adc_result
void HAL_adc_start_conversion (uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result(void);

View file

@ -199,11 +199,11 @@
if(spiRate > 6) spiRate = 1; if(spiRate > 6) spiRate = 1;
#if MB(ALLIGATOR) #if MB(ALLIGATOR)
// Set SPI mode 1, clock, select not active after transfer, with delay between transfers // Set SPI mode 1, clock, select not active after transfer, with delay between transfers
SPI_ConfigureNPCS(SPI0, SPI_CHAN_DAC, SPI_ConfigureNPCS(SPI0, SPI_CHAN_DAC,
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) | SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
SPI_CSR_DLYBCT(1)); SPI_CSR_DLYBCT(1));
// Set SPI mode 0, clock, select not active after transfer, with delay between transfers // Set SPI mode 0, clock, select not active after transfer, with delay between transfers
SPI_ConfigureNPCS(SPI0, SPI_CHAN_EEPROM1, SPI_CSR_NCPHA | SPI_ConfigureNPCS(SPI0, SPI_CHAN_EEPROM1, SPI_CSR_NCPHA |
SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) | SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDueDividors[spiRate]) |
SPI_CSR_DLYBCT(1)); SPI_CSR_DLYBCT(1));

View file

@ -21,7 +21,7 @@
*/ */
#ifdef ARDUINO_ARCH_SAM #ifdef ARDUINO_ARCH_SAM
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG) #if ENABLED(USE_WATCHDOG)

View file

@ -113,7 +113,7 @@ void HAL_adc_enable_channel(int pin) {
}; };
} }
void HAL_adc_start_conversion(uint8_t adc_pin) { void HAL_adc_start_conversion(const uint8_t adc_pin) {
if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) { if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) {
usb_serial.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin); usb_serial.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
return; return;

View file

@ -91,7 +91,7 @@ uint8_t spiRec(uint32_t chan);
void HAL_adc_init(void); void HAL_adc_init(void);
void HAL_adc_enable_channel(int pin); void HAL_adc_enable_channel(int pin);
void HAL_adc_start_conversion (uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result(void);
#endif // _HAL_LPC1768_H #endif // _HAL_LPC1768_H

View file

@ -35,606 +35,301 @@ volatile uint32_t UART0RxQueueWritePos = 0, UART1RxQueueWritePos = 0, UART2RxQue
volatile uint32_t UART0RxQueueReadPos = 0, UART1RxQueueReadPos = 0, UART2RxQueueReadPos = 0, UART3RxQueueReadPos = 0; volatile uint32_t UART0RxQueueReadPos = 0, UART1RxQueueReadPos = 0, UART2RxQueueReadPos = 0, UART3RxQueueReadPos = 0;
volatile uint8_t dummy; volatile uint8_t dummy;
void HardwareSerial::begin(uint32_t baudrate) { void HardwareSerial::begin(uint32_t baudrate) {
uint32_t Fdiv; uint32_t Fdiv, pclkdiv, pclk;
uint32_t pclkdiv, pclk;
if ( PortNum == 0 ) if (PortNum == 0) {
{ LPC_PINCON->PINSEL0 &= ~0x000000F0;
LPC_PINCON->PINSEL0 &= ~0x000000F0; LPC_PINCON->PINSEL0 |= 0x00000050; /* RxD0 is P0.3 and TxD0 is P0.2 */
LPC_PINCON->PINSEL0 |= 0x00000050; /* RxD0 is P0.3 and TxD0 is P0.2 */ /* By default, the PCLKSELx value is zero, thus, the PCLK for
/* By default, the PCLKSELx value is zero, thus, the PCLK for all the peripherals is 1/4 of the SystemFrequency. */
all the peripherals is 1/4 of the SystemFrequency. */ /* Bit 6~7 is for UART0 */
/* Bit 6~7 is for UART0 */ pclkdiv = (LPC_SC->PCLKSEL0 >> 6) & 0x03;
pclkdiv = (LPC_SC->PCLKSEL0 >> 6) & 0x03; switch (pclkdiv) {
switch ( pclkdiv ) case 0x00:
{ default:
case 0x00: pclk = SystemCoreClock / 4;
default: break;
pclk = SystemCoreClock/4; case 0x01:
break; pclk = SystemCoreClock;
case 0x01: break;
pclk = SystemCoreClock; case 0x02:
break; pclk = SystemCoreClock / 2;
case 0x02: break;
pclk = SystemCoreClock/2; case 0x03:
break; pclk = SystemCoreClock / 8;
case 0x03: break;
pclk = SystemCoreClock/8;
break;
}
LPC_UART0->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */
LPC_UART0->DLM = Fdiv / 256;
LPC_UART0->DLL = Fdiv % 256;
LPC_UART0->LCR = 0x03; /* DLAB = 0 */
LPC_UART0->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART0_IRQn);
LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART0 interrupt */
}
else if ( PortNum == 1 )
{
LPC_PINCON->PINSEL4 &= ~0x0000000F;
LPC_PINCON->PINSEL4 |= 0x0000000A; /* Enable RxD1 P2.1, TxD1 P2.0 */
/* By default, the PCLKSELx value is zero, thus, the PCLK for
all the peripherals is 1/4 of the SystemFrequency. */
/* Bit 8,9 are for UART1 */
pclkdiv = (LPC_SC->PCLKSEL0 >> 8) & 0x03;
switch ( pclkdiv )
{
case 0x00:
default:
pclk = SystemCoreClock/4;
break;
case 0x01:
pclk = SystemCoreClock;
break;
case 0x02:
pclk = SystemCoreClock/2;
break;
case 0x03:
pclk = SystemCoreClock/8;
break;
}
LPC_UART1->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */
LPC_UART1->DLM = Fdiv / 256;
LPC_UART1->DLL = Fdiv % 256;
LPC_UART1->LCR = 0x03; /* DLAB = 0 */
LPC_UART1->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART1_IRQn);
LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART1 interrupt */
}
else if ( PortNum == 2 )
{
//LPC_PINCON->PINSEL4 &= ~0x000F0000; /*Pinsel4 Bits 16-19*/
//LPC_PINCON->PINSEL4 |= 0x000A0000; /* RxD2 is P2.9 and TxD2 is P2.8, value 10*/
LPC_PINCON->PINSEL0 &= ~0x00F00000; /*Pinsel0 Bits 20-23*/
LPC_PINCON->PINSEL0 |= 0x00500000; /* RxD2 is P0.11 and TxD2 is P0.10, value 01*/
LPC_SC->PCONP |= 1<<24; //Enable PCUART2
/* By default, the PCLKSELx value is zero, thus, the PCLK for
all the peripherals is 1/4 of the SystemFrequency. */
/* Bit 6~7 is for UART3 */
pclkdiv = (LPC_SC->PCLKSEL1 >> 16) & 0x03;
switch ( pclkdiv )
{
case 0x00:
default:
pclk = SystemCoreClock/4;
break;
case 0x01:
pclk = SystemCoreClock;
break;
case 0x02:
pclk = SystemCoreClock/2;
break;
case 0x03:
pclk = SystemCoreClock/8;
break;
}
LPC_UART2->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */
LPC_UART2->DLM = Fdiv / 256;
LPC_UART2->DLL = Fdiv % 256;
LPC_UART2->LCR = 0x03; /* DLAB = 0 */
LPC_UART2->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART2_IRQn);
LPC_UART2->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART3 interrupt */
}
else if ( PortNum == 3 )
{
LPC_PINCON->PINSEL0 &= ~0x0000000F;
LPC_PINCON->PINSEL0 |= 0x0000000A; /* RxD3 is P0.1 and TxD3 is P0.0 */
LPC_SC->PCONP |= 1<<4 | 1<<25; //Enable PCUART1
/* By default, the PCLKSELx value is zero, thus, the PCLK for
all the peripherals is 1/4 of the SystemFrequency. */
/* Bit 6~7 is for UART3 */
pclkdiv = (LPC_SC->PCLKSEL1 >> 18) & 0x03;
switch ( pclkdiv )
{
case 0x00:
default:
pclk = SystemCoreClock/4;
break;
case 0x01:
pclk = SystemCoreClock;
break;
case 0x02:
pclk = SystemCoreClock/2;
break;
case 0x03:
pclk = SystemCoreClock/8;
break;
}
LPC_UART3->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */
LPC_UART3->DLM = Fdiv / 256;
LPC_UART3->DLL = Fdiv % 256;
LPC_UART3->LCR = 0x03; /* DLAB = 0 */
LPC_UART3->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART3_IRQn);
LPC_UART3->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART3 interrupt */
}
}
int HardwareSerial::read() {
uint8_t rx;
if ( PortNum == 0 )
{
if (UART0RxQueueReadPos == UART0RxQueueWritePos)
return -1;
// Read from "head"
rx = UART0Buffer[UART0RxQueueReadPos]; // grab next byte
UART0RxQueueReadPos = (UART0RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if ( PortNum == 1 )
{
if (UART1RxQueueReadPos == UART1RxQueueWritePos)
return -1;
// Read from "head"
rx = UART1Buffer[UART1RxQueueReadPos]; // grab next byte
UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if ( PortNum == 2 )
{
if (UART2RxQueueReadPos == UART2RxQueueWritePos)
return -1;
// Read from "head"
rx = UART2Buffer[UART2RxQueueReadPos]; // grab next byte
UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if ( PortNum == 3 )
{
if (UART3RxQueueReadPos == UART3RxQueueWritePos)
return -1;
// Read from "head"
rx = UART3Buffer[UART3RxQueueReadPos]; // grab next byte
UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
return 0;
}
size_t HardwareSerial::write(uint8_t send) {
if ( PortNum == 0 )
{
/* THRE status, contain valid data */
while ( !(UART0TxEmpty & 0x01) );
LPC_UART0->THR = send;
UART0TxEmpty = 0; /* not empty in the THR until it shifts out */
}
else if (PortNum == 1)
{
/* THRE status, contain valid data */
while ( !(UART1TxEmpty & 0x01) );
LPC_UART1->THR = send;
UART1TxEmpty = 0; /* not empty in the THR until it shifts out */
}
else if ( PortNum == 2 )
{
/* THRE status, contain valid data */
while ( !(UART2TxEmpty & 0x01) );
LPC_UART2->THR = send;
UART2TxEmpty = 0; /* not empty in the THR until it shifts out */
}
else if ( PortNum == 3 )
{
/* THRE status, contain valid data */
while ( !(UART3TxEmpty & 0x01) );
LPC_UART3->THR = send;
UART3TxEmpty = 0; /* not empty in the THR until it shifts out */
}
return 0;
}
int HardwareSerial::available() {
if ( PortNum == 0 )
{
return (UART0RxQueueWritePos + UARTRXQUEUESIZE - UART0RxQueueReadPos) % UARTRXQUEUESIZE;
}
if ( PortNum == 1 )
{
return (UART1RxQueueWritePos + UARTRXQUEUESIZE - UART1RxQueueReadPos) % UARTRXQUEUESIZE;
}
if ( PortNum == 2 )
{
return (UART2RxQueueWritePos + UARTRXQUEUESIZE - UART2RxQueueReadPos) % UARTRXQUEUESIZE;
}
if ( PortNum == 3 )
{
return (UART3RxQueueWritePos + UARTRXQUEUESIZE - UART3RxQueueReadPos) % UARTRXQUEUESIZE;
}
return 0;
}
void HardwareSerial::flush() {
if ( PortNum == 0 )
{
UART0RxQueueWritePos = 0;
UART0RxQueueReadPos = 0;
}
if ( PortNum == 1 )
{
UART1RxQueueWritePos = 0;
UART1RxQueueReadPos = 0;
}
if ( PortNum == 2 )
{
UART2RxQueueWritePos = 0;
UART2RxQueueReadPos = 0;
}
if ( PortNum == 3 )
{
UART3RxQueueWritePos = 0;
UART3RxQueueReadPos = 0;
}
return;
}
void HardwareSerial::printf(const char *format, ...) {
static char buffer[256];
va_list vArgs;
va_start(vArgs, format);
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
va_end(vArgs);
if (length > 0 && length < 256) {
for (int i = 0; i < length;) {
write(buffer[i]);
++i;
}
}
} }
LPC_UART0->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */
LPC_UART0->DLM = Fdiv / 256;
LPC_UART0->DLL = Fdiv % 256;
LPC_UART0->LCR = 0x03; /* DLAB = 0 */
LPC_UART0->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART0_IRQn);
LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART0 interrupt */
}
else if (PortNum == 1) {
LPC_PINCON->PINSEL4 &= ~0x0000000F;
LPC_PINCON->PINSEL4 |= 0x0000000A; /* Enable RxD1 P2.1, TxD1 P2.0 */
/* By default, the PCLKSELx value is zero, thus, the PCLK for
all the peripherals is 1/4 of the SystemFrequency. */
/* Bit 8,9 are for UART1 */
pclkdiv = (LPC_SC->PCLKSEL0 >> 8) & 0x03;
switch (pclkdiv) {
case 0x00:
default:
pclk = SystemCoreClock / 4;
break;
case 0x01:
pclk = SystemCoreClock;
break;
case 0x02:
pclk = SystemCoreClock / 2;
break;
case 0x03:
pclk = SystemCoreClock / 8;
break;
}
LPC_UART1->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */
LPC_UART1->DLM = Fdiv / 256;
LPC_UART1->DLL = Fdiv % 256;
LPC_UART1->LCR = 0x03; /* DLAB = 0 */
LPC_UART1->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART1_IRQn);
LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART1 interrupt */
}
else if (PortNum == 2) {
//LPC_PINCON->PINSEL4 &= ~0x000F0000; /*Pinsel4 Bits 16-19*/
//LPC_PINCON->PINSEL4 |= 0x000A0000; /* RxD2 is P2.9 and TxD2 is P2.8, value 10*/
LPC_PINCON->PINSEL0 &= ~0x00F00000; /*Pinsel0 Bits 20-23*/
LPC_PINCON->PINSEL0 |= 0x00500000; /* RxD2 is P0.11 and TxD2 is P0.10, value 01*/
LPC_SC->PCONP |= 1 << 24; //Enable PCUART2
/* By default, the PCLKSELx value is zero, thus, the PCLK for
all the peripherals is 1/4 of the SystemFrequency. */
/* Bit 6~7 is for UART3 */
pclkdiv = (LPC_SC->PCLKSEL1 >> 16) & 0x03;
switch (pclkdiv) {
case 0x00:
default:
pclk = SystemCoreClock / 4;
break;
case 0x01:
pclk = SystemCoreClock;
break;
case 0x02:
pclk = SystemCoreClock / 2;
break;
case 0x03:
pclk = SystemCoreClock / 8;
break;
}
LPC_UART2->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = (pclk / 16) / baudrate; /*baud rate */
LPC_UART2->DLM = Fdiv >> 8;
LPC_UART2->DLL = Fdiv & 0xFF;
LPC_UART2->LCR = 0x03; /* DLAB = 0 */
LPC_UART2->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART2_IRQn);
LPC_UART2->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART3 interrupt */
}
else if (PortNum == 3) {
LPC_PINCON->PINSEL0 &= ~0x0000000F;
LPC_PINCON->PINSEL0 |= 0x0000000A; /* RxD3 is P0.1 and TxD3 is P0.0 */
LPC_SC->PCONP |= 1 << 4 | 1 << 25; //Enable PCUART1
/* By default, the PCLKSELx value is zero, thus, the PCLK for
all the peripherals is 1/4 of the SystemFrequency. */
/* Bit 6~7 is for UART3 */
pclkdiv = (LPC_SC->PCLKSEL1 >> 18) & 0x03;
switch (pclkdiv) {
case 0x00:
default:
pclk = SystemCoreClock / 4;
break;
case 0x01:
pclk = SystemCoreClock;
break;
case 0x02:
pclk = SystemCoreClock / 2;
break;
case 0x03:
pclk = SystemCoreClock / 8;
break;
}
LPC_UART3->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
Fdiv = (pclk / 16) / baudrate ; /*baud rate */
LPC_UART3->DLM = Fdiv >> 8;
LPC_UART3->DLL = Fdiv & 0xFF;
LPC_UART3->LCR = 0x03; /* DLAB = 0 */
LPC_UART3->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
NVIC_EnableIRQ(UART3_IRQn);
LPC_UART3->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART3 interrupt */
}
}
int HardwareSerial::read() {
uint8_t rx;
if (PortNum == 0) {
if (UART0RxQueueReadPos == UART0RxQueueWritePos) return -1;
// Read from "head"
rx = UART0Buffer[UART0RxQueueReadPos]; // grab next byte
UART0RxQueueReadPos = (UART0RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if (PortNum == 1) {
if (UART1RxQueueReadPos == UART1RxQueueWritePos) return -1;
rx = UART1Buffer[UART1RxQueueReadPos];
UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if (PortNum == 2) {
if (UART2RxQueueReadPos == UART2RxQueueWritePos) return -1;
rx = UART2Buffer[UART2RxQueueReadPos];
UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if (PortNum == 3) {
if (UART3RxQueueReadPos == UART3RxQueueWritePos) return -1;
rx = UART3Buffer[UART3RxQueueReadPos];
UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
return 0;
}
size_t HardwareSerial::write(uint8_t send) {
if (PortNum == 0) {
/* THRE status, contain valid data */
while (!(UART0TxEmpty & 0x01));
LPC_UART0->THR = send;
UART0TxEmpty = 0; /* not empty in the THR until it shifts out */
}
else if (PortNum == 1) {
while (!(UART1TxEmpty & 0x01));
LPC_UART1->THR = send;
UART1TxEmpty = 0;
}
else if (PortNum == 2) {
while (!(UART2TxEmpty & 0x01));
LPC_UART2->THR = send;
UART2TxEmpty = 0;
}
else if (PortNum == 3) {
while (!(UART3TxEmpty & 0x01));
LPC_UART3->THR = send;
UART3TxEmpty = 0;
}
return 0;
}
int HardwareSerial::available() {
if (PortNum == 0)
return (UART0RxQueueWritePos + UARTRXQUEUESIZE - UART0RxQueueReadPos) % UARTRXQUEUESIZE;
if (PortNum == 1)
return (UART1RxQueueWritePos + UARTRXQUEUESIZE - UART1RxQueueReadPos) % UARTRXQUEUESIZE;
if (PortNum == 2)
return (UART2RxQueueWritePos + UARTRXQUEUESIZE - UART2RxQueueReadPos) % UARTRXQUEUESIZE;
if (PortNum == 3)
return (UART3RxQueueWritePos + UARTRXQUEUESIZE - UART3RxQueueReadPos) % UARTRXQUEUESIZE;
return 0;
}
void HardwareSerial::flush() {
if (PortNum == 0)
UART0RxQueueWritePos = UART0RxQueueReadPos = 0;
if (PortNum == 1)
UART1RxQueueWritePos = UART1RxQueueReadPos = 0;
if (PortNum == 2)
UART2RxQueueWritePos = UART2RxQueueReadPos = 0;
if (PortNum == 3)
UART3RxQueueWritePos = UART3RxQueueReadPos = 0;
}
void HardwareSerial::printf(const char *format, ...) {
static char buffer[256];
va_list vArgs;
va_start(vArgs, format);
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
va_end(vArgs);
if (length > 0 && length < 256)
for (int i = 0; i < length; ++i)
write(buffer[i]);
}
/*****************************************************************************
** Function name: UARTn_IRQHandler
**
** Descriptions: UARTn interrupt handler
**
** parameters: None
** Returned value: None
**
*****************************************************************************/
#define DEFINE_UART_HANDLER(NUM) \
void UART3_IRQHandler(void) { \
uint8_t IIRValue, LSRValue; \
uint8_t Dummy = Dummy; \
IIRValue = LPC_UART ##NUM## ->IIR; \
IIRValue >>= 1; \
IIRValue &= 0x07; \
switch (IIRValue) { \
case IIR_RLS: \
LSRValue = LPC_UART ##NUM## ->LSR; \
if (LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI)) { \
UART ##NUM## Status = LSRValue; \
Dummy = LPC_UART ##NUM## ->RBR; \
return; \
} \
if (LSRValue & LSR_RDR) { \
if ((UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE != UART ##NUM## RxQueueReadPos) { \
UART ##NUM## Buffer[UART ##NUM## RxQueueWritePos] = LPC_UART ##NUM## ->RBR; \
UART ##NUM## RxQueueWritePos = (UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE; \
} \
} \
break; \
case IIR_RDA: \
if ((UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE != UART ##NUM## RxQueueReadPos) { \
UART ##NUM## Buffer[UART ##NUM## RxQueueWritePos] = LPC_UART ##NUM## ->RBR; \
UART ##NUM## RxQueueWritePos = (UART ##NUM## RxQueueWritePos+1) % UARTRXQUEUESIZE; \
} \
else \
dummy = LPC_UART ##NUM## ->RBR;; \
break; \
case IIR_CTI: \
UART ##NUM## Status |= 0x100; \
break; \
case IIR_THRE: \
LSRValue = LPC_UART ##NUM## ->LSR; \
UART ##NUM## TxEmpty = (LSRValue & LSR_THRE) ? 1 : 0; \
break; \
} \
} \
typedef void _uart_ ## NUM
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
/***************************************************************************** DEFINE_UART_HANDLER(0);
** Function name: UART0_IRQHandler DEFINE_UART_HANDLER(1);
** DEFINE_UART_HANDLER(2);
** Descriptions: UART0 interrupt handler DEFINE_UART_HANDLER(3);
**
** parameters: None
** Returned value: None
**
*****************************************************************************/
void UART0_IRQHandler (void)
{
uint8_t IIRValue, LSRValue;
uint8_t Dummy = Dummy;
IIRValue = LPC_UART0->IIR;
IIRValue >>= 1; /* skip pending bit in IIR */
IIRValue &= 0x07; /* check bit 1~3, interrupt identification */
if ( IIRValue == IIR_RLS ) /* Receive Line Status */
{
LSRValue = LPC_UART0->LSR;
/* Receive Line Status */
if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
{
/* There are errors or break interrupt */
/* Read LSR will clear the interrupt */
UART0Status = LSRValue;
Dummy = LPC_UART0->RBR; /* Dummy read on RX to clear
interrupt, then bail out */
return;
}
if ( LSRValue & LSR_RDR ) /* Receive Data Ready */
{
/* If no error on RLS, normal ready, save into the data buffer. */
/* Note: read RBR will clear the interrupt */
if ((UART0RxQueueWritePos+1) % UARTRXQUEUESIZE != UART0RxQueueReadPos)
{
UART0Buffer[UART0RxQueueWritePos] = LPC_UART0->RBR;
UART0RxQueueWritePos = (UART0RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
else
dummy = LPC_UART0->RBR;;
}
}
else if ( IIRValue == IIR_RDA ) /* Receive Data Available */
{
/* Receive Data Available */
if ((UART0RxQueueWritePos+1) % UARTRXQUEUESIZE != UART0RxQueueReadPos)
{
UART0Buffer[UART0RxQueueWritePos] = LPC_UART0->RBR;
UART0RxQueueWritePos = (UART0RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
else
dummy = LPC_UART1->RBR;;
}
else if ( IIRValue == IIR_CTI ) /* Character timeout indicator */
{
/* Character Time-out indicator */
UART0Status |= 0x100; /* Bit 9 as the CTI error */
}
else if ( IIRValue == IIR_THRE ) /* THRE, transmit holding register empty */
{
/* THRE interrupt */
LSRValue = LPC_UART0->LSR; /* Check status in the LSR to see if
valid data in U0THR or not */
if ( LSRValue & LSR_THRE )
{
UART0TxEmpty = 1;
}
else
{
UART0TxEmpty = 0;
}
}
}
/*****************************************************************************
** Function name: UART1_IRQHandler
**
** Descriptions: UART1 interrupt handler
**
** parameters: None
** Returned value: None
**
*****************************************************************************/
void UART1_IRQHandler (void)
{
uint8_t IIRValue, LSRValue;
uint8_t Dummy = Dummy;
IIRValue = LPC_UART1->IIR;
IIRValue >>= 1; /* skip pending bit in IIR */
IIRValue &= 0x07; /* check bit 1~3, interrupt identification */
if ( IIRValue == IIR_RLS ) /* Receive Line Status */
{
LSRValue = LPC_UART1->LSR;
/* Receive Line Status */
if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
{
/* There are errors or break interrupt */
/* Read LSR will clear the interrupt */
UART1Status = LSRValue;
Dummy = LPC_UART1->RBR; /* Dummy read on RX to clear
interrupt, then bail out */
return;
}
if ( LSRValue & LSR_RDR ) /* Receive Data Ready */
{
/* If no error on RLS, normal ready, save into the data buffer. */
/* Note: read RBR will clear the interrupt */
if ((UART1RxQueueWritePos+1) % UARTRXQUEUESIZE != UART1RxQueueReadPos)
{
UART1Buffer[UART1RxQueueWritePos] = LPC_UART1->RBR;
UART1RxQueueWritePos =(UART1RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
else
dummy = LPC_UART1->RBR;;
}
}
else if ( IIRValue == IIR_RDA ) /* Receive Data Available */
{
/* Receive Data Available */
if ((UART1RxQueueWritePos+1) % UARTRXQUEUESIZE != UART1RxQueueReadPos)
{
UART1Buffer[UART1RxQueueWritePos] = LPC_UART1->RBR;
UART1RxQueueWritePos = (UART1RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
else
dummy = LPC_UART1->RBR;;
}
else if ( IIRValue == IIR_CTI ) /* Character timeout indicator */
{
/* Character Time-out indicator */
UART1Status |= 0x100; /* Bit 9 as the CTI error */
}
else if ( IIRValue == IIR_THRE ) /* THRE, transmit holding register empty */
{
/* THRE interrupt */
LSRValue = LPC_UART1->LSR; /* Check status in the LSR to see if
valid data in U0THR or not */
if ( LSRValue & LSR_THRE )
{
UART1TxEmpty = 1;
}
else
{
UART1TxEmpty = 0;
}
}
}
/*****************************************************************************
** Function name: UART2_IRQHandler
**
** Descriptions: UART2 interrupt handler
**
** parameters: None
** Returned value: None
**
*****************************************************************************/
void UART2_IRQHandler (void)
{
uint8_t IIRValue, LSRValue;
uint8_t Dummy = Dummy;
IIRValue = LPC_UART2->IIR;
IIRValue >>= 1; /* skip pending bit in IIR */
IIRValue &= 0x07; /* check bit 1~3, interrupt identification */
if ( IIRValue == IIR_RLS ) /* Receive Line Status */
{
LSRValue = LPC_UART2->LSR;
/* Receive Line Status */
if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
{
/* There are errors or break interrupt */
/* Read LSR will clear the interrupt */
UART2Status = LSRValue;
Dummy = LPC_UART2->RBR; /* Dummy read on RX to clear
interrupt, then bail out */
return;
}
if ( LSRValue & LSR_RDR ) /* Receive Data Ready */
{
/* If no error on RLS, normal ready, save into the data buffer. */
/* Note: read RBR will clear the interrupt */
if ((UART2RxQueueWritePos+1) % UARTRXQUEUESIZE != UART2RxQueueReadPos)
{
UART2Buffer[UART2RxQueueWritePos] = LPC_UART2->RBR;
UART2RxQueueWritePos = (UART2RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
}
}
else if ( IIRValue == IIR_RDA ) /* Receive Data Available */
{
/* Receive Data Available */
if ((UART2RxQueueWritePos+1) % UARTRXQUEUESIZE != UART2RxQueueReadPos)
{
UART2Buffer[UART2RxQueueWritePos] = LPC_UART2->RBR;
UART2RxQueueWritePos = (UART2RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
else
dummy = LPC_UART2->RBR;;
}
else if ( IIRValue == IIR_CTI ) /* Character timeout indicator */
{
/* Character Time-out indicator */
UART2Status |= 0x100; /* Bit 9 as the CTI error */
}
else if ( IIRValue == IIR_THRE ) /* THRE, transmit holding register empty */
{
/* THRE interrupt */
LSRValue = LPC_UART2->LSR; /* Check status in the LSR to see if
valid data in U0THR or not */
if ( LSRValue & LSR_THRE )
{
UART2TxEmpty = 1;
}
else
{
UART2TxEmpty = 0;
}
}
}
/*****************************************************************************
** Function name: UART3_IRQHandler
**
** Descriptions: UART0 interrupt handler
**
** parameters: None
** Returned value: None
**
*****************************************************************************/
void UART3_IRQHandler (void)
{
uint8_t IIRValue, LSRValue;
uint8_t Dummy = Dummy;
IIRValue = LPC_UART3->IIR;
IIRValue >>= 1; /* skip pending bit in IIR */
IIRValue &= 0x07; /* check bit 1~3, interrupt identification */
if ( IIRValue == IIR_RLS ) /* Receive Line Status */
{
LSRValue = LPC_UART3->LSR;
/* Receive Line Status */
if ( LSRValue & (LSR_OE|LSR_PE|LSR_FE|LSR_RXFE|LSR_BI) )
{
/* There are errors or break interrupt */
/* Read LSR will clear the interrupt */
UART3Status = LSRValue;
Dummy = LPC_UART3->RBR; /* Dummy read on RX to clear
interrupt, then bail out */
return;
}
if ( LSRValue & LSR_RDR ) /* Receive Data Ready */
{
/* If no error on RLS, normal ready, save into the data buffer. */
/* Note: read RBR will clear the interrupt */
if ((UART3RxQueueWritePos+1) % UARTRXQUEUESIZE != UART3RxQueueReadPos)
{
UART3Buffer[UART3RxQueueWritePos] = LPC_UART3->RBR;
UART3RxQueueWritePos = (UART3RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
}
}
else if ( IIRValue == IIR_RDA ) /* Receive Data Available */
{
/* Receive Data Available */
if ((UART3RxQueueWritePos+1) % UARTRXQUEUESIZE != UART3RxQueueReadPos)
{
UART3Buffer[UART3RxQueueWritePos] = LPC_UART3->RBR;
UART3RxQueueWritePos = (UART3RxQueueWritePos+1) % UARTRXQUEUESIZE;
}
else
dummy = LPC_UART3->RBR;;
}
else if ( IIRValue == IIR_CTI ) /* Character timeout indicator */
{
/* Character Time-out indicator */
UART3Status |= 0x100; /* Bit 9 as the CTI error */
}
else if ( IIRValue == IIR_THRE ) /* THRE, transmit holding register empty */
{
/* THRE interrupt */
LSRValue = LPC_UART3->LSR; /* Check status in the LSR to see if
valid data in U0THR or not */
if ( LSRValue & LSR_THRE )
{
UART3TxEmpty = 1;
}
else
{
UART3TxEmpty = 0;
}
}
}
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif
#endif // TARGET_LPC1768 #endif // TARGET_LPC1768

View file

@ -29,30 +29,29 @@
extern "C" { extern "C" {
#include <debug_frmwrk.h> #include <debug_frmwrk.h>
//#include <lpc17xx_uart.h>
//#include <lpc17xx_uart.h>
} }
#define IER_RBR 0x01 #define IER_RBR 0x01
#define IER_THRE 0x02 #define IER_THRE 0x02
#define IER_RLS 0x04 #define IER_RLS 0x04
#define IIR_PEND 0x01 #define IIR_PEND 0x01
#define IIR_RLS 0x03 #define IIR_RLS 0x03
#define IIR_RDA 0x02 #define IIR_RDA 0x02
#define IIR_CTI 0x06 #define IIR_CTI 0x06
#define IIR_THRE 0x01 #define IIR_THRE 0x01
#define LSR_RDR 0x01 #define LSR_RDR 0x01
#define LSR_OE 0x02 #define LSR_OE 0x02
#define LSR_PE 0x04 #define LSR_PE 0x04
#define LSR_FE 0x08 #define LSR_FE 0x08
#define LSR_BI 0x10 #define LSR_BI 0x10
#define LSR_THRE 0x20 #define LSR_THRE 0x20
#define LSR_TEMT 0x40 #define LSR_TEMT 0x40
#define LSR_RXFE 0x80 #define LSR_RXFE 0x80
#define UARTRXQUEUESIZE 0x10 #define UARTRXQUEUESIZE 0x10
class HardwareSerial : public Stream { class HardwareSerial : public Stream {
private: private:
@ -75,75 +74,35 @@ public:
return 0; return 0;
}; };
operator bool() { return true; }
operator bool() { void print(const char value[]) { printf("%s" , value); }
return true; void print(char value, int = 0) { printf("%c" , value); }
} void print(unsigned char value, int = 0) { printf("%u" , value); }
void print(int value, int = 0) { printf("%d" , value); }
void print(unsigned int value, int = 0) { printf("%u" , value); }
void print(long value, int = 0) { printf("%ld" , value); }
void print(unsigned long value, int = 0) { printf("%lu" , value); }
void print(const char value[]) { void print(float value, int round = 6) { printf("%f" , value); }
printf("%s" , value); void print(double value, int round = 6) { printf("%f" , value ); }
}
void print(char value, int = 0) {
printf("%c" , value);
}
void print(unsigned char value, int = 0) {
printf("%u" , value);
}
void print(int value, int = 0) {
printf("%d" , value);
}
void print(unsigned int value, int = 0) {
printf("%u" , value);
}
void print(long value, int = 0) {
printf("%ld" , value);
}
void print(unsigned long value, int = 0) {
printf("%lu" , value);
}
void print(float value, int round = 6) { void println(const char value[]) { printf("%s\n" , value); }
printf("%f" , value); void println(char value, int = 0) { printf("%c\n" , value); }
} void println(unsigned char value, int = 0) { printf("%u\r\n" , value); }
void print(double value, int round = 6) { void println(int value, int = 0) { printf("%d\n" , value); }
printf("%f" , value ); void println(unsigned int value, int = 0) { printf("%u\n" , value); }
} void println(long value, int = 0) { printf("%ld\n" , value); }
void println(unsigned long value, int = 0) { printf("%lu\n" , value); }
void println(const char value[]) { void println(float value, int round = 6) { printf("%f\n" , value ); }
printf("%s\n" , value); void println(double value, int round = 6) { printf("%f\n" , value ); }
} void println(void) { print('\n'); }
void println(char value, int = 0) {
printf("%c\n" , value);
}
void println(unsigned char value, int = 0) {
printf("%u\r\n" , value);
}
void println(int value, int = 0) {
printf("%d\n" , value);
}
void println(unsigned int value, int = 0) {
printf("%u\n" , value);
}
void println(long value, int = 0) {
printf("%ld\n" , value);
}
void println(unsigned long value, int = 0) {
printf("%lu\n" , value);
}
void println(float value, int round = 6) {
printf("%f\n" , value );
}
void println(double value, int round = 6) {
printf("%f\n" , value );
}
void println(void) {
print('\n');
}
}; };
//extern HardwareSerial Serial0; //extern HardwareSerial Serial0;
//extern HardwareSerial Serial1; //extern HardwareSerial Serial1;
//extern HardwareSerial Serial2; //extern HardwareSerial Serial2;
extern HardwareSerial Serial3; extern HardwareSerial Serial3;
#endif /* MARLIN_SRC_HAL_HAL_SERIAL_H_ */ #endif // MARLIN_SRC_HAL_HAL_SERIAL_H_

View file

@ -27,19 +27,19 @@
*/ */
/** /**
* This is a hybrid system. * This is a hybrid system.
* *
* The PWM1 module is used to directly control the Servo 0, 1 & 3 pins. This keeps * The PWM1 module is used to directly control the Servo 0, 1 & 3 pins. This keeps
* the pulse width jitter to under a microsecond. * the pulse width jitter to under a microsecond.
* *
* For all other pins the PWM1 module is used to generate interrupts. The ISR * For all other pins the PWM1 module is used to generate interrupts. The ISR
* routine does the actual setting/clearing of pins. The upside is that any pin can * routine does the actual setting/clearing of pins. The upside is that any pin can
* have a PWM channel assigned to it. The downside is that there is more pulse width * have a PWM channel assigned to it. The downside is that there is more pulse width
* jitter. The jitter depends on what else is happening in the system and what ISRs * jitter. The jitter depends on what else is happening in the system and what ISRs
* prempt the PWM ISR. Writing to the SD card can add 20 microseconds to the pulse * prempt the PWM ISR. Writing to the SD card can add 20 microseconds to the pulse
* width. * width.
*/ */
/** /**
* The data structures are setup to minimize the computation done by the ISR which * The data structures are setup to minimize the computation done by the ISR which
* minimizes ISR execution time. Execution times are 2.2 - 3.7 microseconds. * minimizes ISR execution time. Execution times are 2.2 - 3.7 microseconds.
@ -72,7 +72,7 @@ typedef struct { // holds all data needed to control/init one of the
uint16_t PWM_mask; // MASK TO CHECK/WRITE THE IR REGISTER uint16_t PWM_mask; // MASK TO CHECK/WRITE THE IR REGISTER
volatile uint32_t* set_register; volatile uint32_t* set_register;
volatile uint32_t* clr_register; volatile uint32_t* clr_register;
uint32_t write_mask; // USED BY SET/CLEAR COMMANDS uint32_t write_mask; // USED BY SET/CLEAR COMMANDS
uint32_t microseconds; // value written to MR register uint32_t microseconds; // value written to MR register
uint32_t min; // lower value limit checked by WRITE routine before writing to the MR register uint32_t min; // lower value limit checked by WRITE routine before writing to the MR register
uint32_t max; // upper value limit checked by WRITE routine before writing to the MR register uint32_t max; // upper value limit checked by WRITE routine before writing to the MR register
@ -180,7 +180,7 @@ void LPC1768_PWM_init(void) {
bool PWM_table_swap = false; // flag to tell the ISR that the tables have been swapped bool PWM_table_swap = false; // flag to tell the ISR that the tables have been swapped
bool PWM_MR0_wait = false; // flag to ensure don't delay MR0 interrupt bool PWM_MR0_wait = false; // flag to ensure don't delay MR0 interrupt
bool LPC1768_PWM_attach_pin(uint8_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff) { bool LPC1768_PWM_attach_pin(uint8_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff) {
@ -209,7 +209,7 @@ bool LPC1768_PWM_attach_pin(uint8_t pin, uint32_t min = 1, uint32_t max = (LPC_P
//swap tables //swap tables
PWM_MR0_wait = true; PWM_MR0_wait = true;
while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it. while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it.
NVIC_DisableIRQ(PWM1_IRQn); NVIC_DisableIRQ(PWM1_IRQn);
PWM_map *pointer_swap = active_table; PWM_map *pointer_swap = active_table;
active_table = work_table; active_table = work_table;
@ -235,8 +235,8 @@ typedef struct { // status of PWM1 channel
uint32_t PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control uint32_t PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control
} MR_map; } MR_map;
MR_map map_MR[NUM_PWMS]; MR_map map_MR[NUM_PWMS];
void LPC1768_PWM_update_map_MR(void) { void LPC1768_PWM_update_map_MR(void) {
map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel) ? 1 : 0), 4, &LPC_PWM1->MR1, 0, 0}; map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel) ? 1 : 0), 4, &LPC_PWM1->MR1, 0, 0};
map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0}; map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
@ -244,7 +244,7 @@ void LPC1768_PWM_update_map_MR(void) {
map_MR[3] = {0, 0, 0, &LPC_PWM1->MR4, 0, 0}; map_MR[3] = {0, 0, 0, &LPC_PWM1->MR4, 0, 0};
map_MR[4] = {0, 0, 0, &LPC_PWM1->MR5, 0, 0}; map_MR[4] = {0, 0, 0, &LPC_PWM1->MR5, 0, 0};
map_MR[5] = {0, 0, 0, &LPC_PWM1->MR6, 0, 0}; map_MR[5] = {0, 0, 0, &LPC_PWM1->MR6, 0, 0};
} }
uint32_t LPC1768_PWM_interrupt_mask = 1; uint32_t LPC1768_PWM_interrupt_mask = 1;
@ -265,46 +265,46 @@ void LPC1768_PWM_update(void) {
} }
LPC1768_PWM_interrupt_mask = 0; // set match registers to new values, build IRQ mask LPC1768_PWM_interrupt_mask = 0; // set match registers to new values, build IRQ mask
for (uint8_t i = 0; i < NUM_PWMS; i++) { for (uint8_t i = 0; i < NUM_PWMS; i++) {
if (work_table[i].active_flag == true) { if (work_table[i].active_flag == true) {
work_table[i].sequence = i + 1; work_table[i].sequence = i + 1;
// first see if there is a PWM1 controlled pin for this entry // first see if there is a PWM1 controlled pin for this entry
bool found = false; bool found = false;
for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) { for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {
if ( (map_MR[j].map_PWM_PIN == work_table[i].logical_pin) && map_MR[j].map_PWM_INT ) { if ( (map_MR[j].map_PWM_PIN == work_table[i].logical_pin) && map_MR[j].map_PWM_INT ) {
*map_MR[j].MR_register = work_table[i].microseconds; // found one of the PWM pins *map_MR[j].MR_register = work_table[i].microseconds; // found one of the PWM pins
work_table[i].PWM_mask = 0; work_table[i].PWM_mask = 0;
work_table[i].PCR_bit = map_MR[j].PCR_bit; // PCR register bit to enable PWM1 control of this pin work_table[i].PCR_bit = map_MR[j].PCR_bit; // PCR register bit to enable PWM1 control of this pin
work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control} MR_map; work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control} MR_map;
map_MR[j].map_used = 2; map_MR[j].map_used = 2;
work_table[i].assigned_MR = j +1; // only used to help in debugging work_table[i].assigned_MR = j +1; // only used to help in debugging
found = true; found = true;
} }
} }
// didn't find a PWM1 pin so get an interrupt // didn't find a PWM1 pin so get an interrupt
for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) { for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) { if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
*map_MR[k].MR_register = work_table[i].microseconds; // found one for an interrupt pin *map_MR[k].MR_register = work_table[i].microseconds; // found one for an interrupt pin
map_MR[k].map_used = 1; map_MR[k].map_used = 1;
LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1)); // set bit in the MCR to enable this MR to generate an interrupt LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1)); // set bit in the MCR to enable this MR to generate an interrupt
work_table[i].PWM_mask = _BV(IR_BIT(k + 1)); // bit in the IR that will go active when this MR generates an interrupt work_table[i].PWM_mask = _BV(IR_BIT(k + 1)); // bit in the IR that will go active when this MR generates an interrupt
work_table[i].assigned_MR = k +1; // only used to help in debugging work_table[i].assigned_MR = k +1; // only used to help in debugging
found = true; found = true;
} }
} }
} }
else else
work_table[i].sequence = 0; work_table[i].sequence = 0;
} }
LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0); // add in MR0 interrupt LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0); // add in MR0 interrupt
// swap tables // swap tables
PWM_MR0_wait = true; PWM_MR0_wait = true;
while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it. while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it.
NVIC_DisableIRQ(PWM1_IRQn); NVIC_DisableIRQ(PWM1_IRQn);
LPC_PWM1->LER = 0x07E; // Set the latch Enable Bits to load the new Match Values for MR1 - MR6 LPC_PWM1->LER = 0x07E; // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
PWM_map *pointer_swap = active_table; PWM_map *pointer_swap = active_table;
@ -324,7 +324,7 @@ bool LPC1768_PWM_write(uint8_t pin, uint32_t value) {
if (slot == 0xFF) return false; // return error if pin not found if (slot == 0xFF) return false; // return error if pin not found
LPC1768_PWM_update_map_MR(); LPC1768_PWM_update_map_MR();
switch(pin) { switch(pin) {
case 11: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2) case 11: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel); // enable PWM1 module control of this pin map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel); // enable PWM1 module control of this pin
@ -337,22 +337,22 @@ bool LPC1768_PWM_write(uint8_t pin, uint32_t value) {
map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10; // ISR must do this AFTER setting PCR map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10; // ISR must do this AFTER setting PCR
break; break;
case 4: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1) case 4: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel); // enable PWM1 module control of this pin map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel); // enable PWM1 module control of this pin
map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM
map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0x2 << 4; // ISR must do this AFTER setting PCR map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0x2 << 4; // ISR must do this AFTER setting PCR
break; break;
default: // ISR pins default: // ISR pins
pinMode(pin, OUTPUT); // set pin to output but don't write anything in case it's already in use pinMode(pin, OUTPUT); // set pin to output but don't write anything in case it's already in use
break; break;
} }
work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min); work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
work_table[slot].active_flag = true; work_table[slot].active_flag = true;
LPC1768_PWM_update(); LPC1768_PWM_update();
return 1; return 1;
} }
bool LPC1768_PWM_detach_pin(uint8_t pin) { bool LPC1768_PWM_detach_pin(uint8_t pin) {
@ -382,16 +382,16 @@ bool LPC1768_PWM_detach_pin(uint8_t pin) {
map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
break; break;
case 4: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1) case 4: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel)); // disable PWM1 module control of this pin LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel)); // disable PWM1 module control of this pin
map_MR[pin_4_PWM_channel - 1].PCR_bit = 0; map_MR[pin_4_PWM_channel - 1].PCR_bit = 0;
LPC_PINCON->PINSEL3 &= ~(0x3 << 4); // return pin to general purpose I/O LPC_PINCON->PINSEL3 &= ~(0x3 << 4); // return pin to general purpose I/O
map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0; map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0;
map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
break; break;
} }
pinMode(pin, INPUT); pinMode(pin, INPUT);
work_table[slot] = PWM_MAP_INIT_ROW; work_table[slot] = PWM_MAP_INIT_ROW;
LPC1768_PWM_update(); LPC1768_PWM_update();
@ -411,8 +411,8 @@ bool LPC1768_PWM_detach_pin(uint8_t pin) {
* Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise * Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
* the wrong pin may be toggled or even have the system hang. * the wrong pin may be toggled or even have the system hang.
*/ */
HAL_PWM_LPC1768_ISR { HAL_PWM_LPC1768_ISR {
if (PWM_table_swap) ISR_table = work_table; // use old table if a swap was just done if (PWM_table_swap) ISR_table = work_table; // use old table if a swap was just done
else ISR_table = active_table; else ISR_table = active_table;
@ -422,13 +422,13 @@ HAL_PWM_LPC1768_ISR {
if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
for (uint8_t i = 0; (i < NUM_PWMS) ; i++) { for (uint8_t i = 0; (i < NUM_PWMS) ; i++) {
if(ISR_table[i].active_flag && !((ISR_table[i].logical_pin == 11) || if(ISR_table[i].active_flag && !((ISR_table[i].logical_pin == 11) ||
(ISR_table[i].logical_pin == 4) || (ISR_table[i].logical_pin == 4) ||
(ISR_table[i].logical_pin == 6))) (ISR_table[i].logical_pin == 6)))
*ISR_table[i].set_register = ISR_table[i].write_mask; // set pins for all enabled interrupt channels active *ISR_table[i].set_register = ISR_table[i].write_mask; // set pins for all enabled interrupt channels active
if (PWM_table_swap && ISR_table[i].PCR_bit) { if (PWM_table_swap && ISR_table[i].PCR_bit) {
LPC_PWM1->PCR |= ISR_table[i].PCR_bit; // enable PWM1 module control of this pin LPC_PWM1->PCR |= ISR_table[i].PCR_bit; // enable PWM1 module control of this pin
LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits; // set pin mode to PWM1 control - must be done after PCR LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits; // set pin mode to PWM1 control - must be done after PCR
} }
} }
PWM_table_swap = false; PWM_table_swap = false;
@ -442,7 +442,7 @@ HAL_PWM_LPC1768_ISR {
*ISR_table[i].clr_register = ISR_table[i].write_mask; // set channel to inactive *ISR_table[i].clr_register = ISR_table[i].write_mask; // set channel to inactive
} }
} }
LPC_PWM1->IR = 0x70F; // guarantees all interrupt flags are cleared which, if there is an unexpected LPC_PWM1->IR = 0x70F; // guarantees all interrupt flags are cleared which, if there is an unexpected
// PWM interrupt, will keep the ISR from hanging which will crash the controller // PWM interrupt, will keep the ISR from hanging which will crash the controller
@ -457,20 +457,20 @@ return;
/** /**
* Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0) * Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
* interrupt. The only exception is detaching pins. It doesn't matter when they go * interrupt. The only exception is detaching pins. It doesn't matter when they go
* tristate. * tristate.
* *
* The LPC1768_PWM_init routine kicks off the MR0 interrupt. This interrupt is never disabled or * The LPC1768_PWM_init routine kicks off the MR0 interrupt. This interrupt is never disabled or
* delayed. * delayed.
* *
* The PWM_table_swap flag is set when the firmware has swapped in an updated table. It is * The PWM_table_swap flag is set when the firmware has swapped in an updated table. It is
* cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates. * cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
* It serves two purposes: * It serves two purposes:
* 1) Tells the ISR that the tables have been swapped * 1) Tells the ISR that the tables have been swapped
* 2) Keeps the firmware from starting a new update until the previous one has been completed. * 2) Keeps the firmware from starting a new update until the previous one has been completed.
* *
* The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by * The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
* the ISR during the MR0 interrupt. It is used to avoid delaying the MR0 interrupt when swapping in * the ISR during the MR0 interrupt. It is used to avoid delaying the MR0 interrupt when swapping in
* an updated table. This avoids glitches in pulse width and/or repetition rate. * an updated table. This avoids glitches in pulse width and/or repetition rate.
* *
* The sequence of events during a write to a PWM channel is: * The sequence of events during a write to a PWM channel is:
* 1) Waits until PWM_table_swap flag is false before starting * 1) Waits until PWM_table_swap flag is false before starting
@ -489,7 +489,7 @@ return;
* writes to the LER register * writes to the LER register
* sets the PWM_table_swap flag active * sets the PWM_table_swap flag active
* re-enables the ISR * re-enables the ISR
* 7) On the next interrupt the ISR changes its pointer to the work table which is now the old, * 7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
* unmodified, active table. * unmodified, active table.
* 8) On the next MR0 interrupt the ISR: * 8) On the next MR0 interrupt the ISR:
* switches over to the active table * switches over to the active table
@ -500,4 +500,4 @@ return;
* NOTE - PCR must be set before PINSEL * NOTE - PCR must be set before PINSEL
* sets the pins controlled by the ISR to their active states * sets the pins controlled by the ISR to their active states
*/ */

View file

@ -89,11 +89,11 @@
this->servoIndex = INVALID_SERVO; // too many servos this->servoIndex = INVALID_SERVO; // too many servos
} }
int8_t Servo::attach(int pin) { int8_t Servo::attach(const int pin) {
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH); return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
} }
int8_t Servo::attach(int pin, int min, int max) { int8_t Servo::attach(const int pin, const int min, const int max) {
if (this->servoIndex >= MAX_SERVOS) return -1; if (this->servoIndex >= MAX_SERVOS) return -1;
@ -113,7 +113,7 @@
servo_info[this->servoIndex].Pin.isActive = false; servo_info[this->servoIndex].Pin.isActive = false;
} }
void Servo::write(int value) { void Servo::write(const int value) {
if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds) if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX()); value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
// odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says // odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says
@ -122,7 +122,7 @@
this->writeMicroseconds(value); this->writeMicroseconds(value);
} }
void Servo::writeMicroseconds(int value) { void Servo::writeMicroseconds(const int value) {
// calculate and store the values for the given channel // calculate and store the values for the given channel
byte channel = this->servoIndex; byte channel = this->servoIndex;
if (channel < MAX_SERVOS) { // ensure channel is valid if (channel < MAX_SERVOS) { // ensure channel is valid
@ -146,7 +146,7 @@
bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; } bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
void Servo::move(int value) { void Servo::move(const int value) {
if (this->attach(0) >= 0) { // notice the pin number is zero here if (this->attach(0) >= 0) { // notice the pin number is zero here
this->write(value); this->write(value);
delay(SERVO_DELAY); delay(SERVO_DELAY);

View file

@ -39,12 +39,12 @@
class Servo { class Servo {
public: public:
Servo(); Servo();
int8_t attach(int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail) int8_t attach(const int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
int8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes. int8_t attach(const int pin, const int min, const int max); // as above but also sets min and max values for writes.
void detach(); void detach();
void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds void write(const int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
void writeMicroseconds(int value); // write pulse width in microseconds void writeMicroseconds(const int value); // write pulse width in microseconds
void move(int value); // attach the servo, then move to value void move(const int value); // attach the servo, then move to value
// if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
// if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach // if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
int read(); // returns current pulse width as an angle between 0 and 180 degrees int read(); // returns current pulse width as an angle between 0 and 180 degrees

View file

@ -88,7 +88,7 @@ static const DELAY_TABLE table[] =
/* static */ /* static */
inline void SoftwareSerial::tunedDelay(uint32_t count) { inline void SoftwareSerial::tunedDelay(uint32_t count) {
asm volatile( asm volatile(
"mov r3, %[loopsPerMicrosecond] \n\t" //load the initial loop counter "mov r3, %[loopsPerMicrosecond] \n\t" //load the initial loop counter
"1: \n\t" "1: \n\t"
@ -163,7 +163,7 @@ void SoftwareSerial::recv()
// Read each of the 8 bits // Read each of the 8 bits
for (uint8_t i=8; i > 0; --i) for (uint8_t i=8; i > 0; --i)
{ {
tunedDelay(_rx_delay_intrabit); tunedDelay(_rx_delay_intrabit);
d >>= 1; d >>= 1;
if (rx_pin_read()) if (rx_pin_read())
d |= 0x80; d |= 0x80;
@ -184,9 +184,9 @@ void SoftwareSerial::recv()
{ {
_buffer_overflow = true; _buffer_overflow = true;
} }
tunedDelay(_rx_delay_stopbit); tunedDelay(_rx_delay_stopbit);
// Re-enable interrupts when we're sure to be inside the stop bit // Re-enable interrupts when we're sure to be inside the stop bit
setRxIntMsk(true);//__enable_irq();// setRxIntMsk(true);//__enable_irq();//
} }
} }
@ -339,7 +339,7 @@ size_t SoftwareSerial::write(uint8_t b)
uint16_t delay = _tx_delay; uint16_t delay = _tx_delay;
if(inv) if(inv)
b = ~b; b = ~b;
cli(); // turn off interrupts for a clean txmit cli(); // turn off interrupts for a clean txmit
@ -369,7 +369,7 @@ size_t SoftwareSerial::write(uint8_t b)
else else
digitalWrite(_transmitPin, 1); digitalWrite(_transmitPin, 1);
sei(); // turn interrupts back on sei(); // turn interrupts back on
tunedDelay(delay); tunedDelay(delay);
return 1; return 1;

View file

@ -25,14 +25,15 @@
#include <lpc17xx_pinsel.h> #include <lpc17xx_pinsel.h>
#include "HAL.h" #include "HAL.h"
#include "../../core/macros.h" #include "../../core/macros.h"
#include "../../core/types.h"
// Interrupts // Interrupts
void cli(void) { __disable_irq(); } // Disable void cli(void) { __disable_irq(); } // Disable
void sei(void) { __enable_irq(); } // Enable void sei(void) { __enable_irq(); } // Enable
// Time functions // Time functions
void _delay_ms(int delay_ms) { void _delay_ms(const int delay_ms) {
delay (delay_ms); delay(delay_ms);
} }
uint32_t millis() { uint32_t millis() {
@ -72,16 +73,16 @@ void delayMicroseconds(uint32_t us) {
} }
} }
extern "C" void delay(int msec) { extern "C" void delay(const int msec) {
volatile int32_t end = _millis + msec; volatile millis_t end = _millis + msec;
SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
// this could extend the time between systicks by upto 1ms // this could extend the time between systicks by upto 1ms
while (_millis < end) __WFE(); while PENDING(_millis, end) __WFE();
} }
// IO functions // IO functions
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2) // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
void pinMode(int pin, int mode) { void pinMode(uint8_t pin, uint8_t mode) {
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
return; return;
@ -109,7 +110,7 @@ void pinMode(int pin, int mode) {
} }
} }
void digitalWrite(int pin, int pin_status) { void digitalWrite(uint8_t pin, uint8_t pin_status) {
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
return; return;
@ -129,16 +130,14 @@ void digitalWrite(int pin, int pin_status) {
*/ */
} }
bool digitalRead(int pin) { bool digitalRead(uint8_t pin) {
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) { if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
return false; return false;
} }
return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0; return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
} }
void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
void analogWrite(int pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t); extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
extern bool LPC1768_PWM_write(uint8_t, uint32_t); extern bool LPC1768_PWM_write(uint8_t, uint32_t);
@ -168,7 +167,7 @@ void analogWrite(int pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255:
extern bool HAL_adc_finished(); extern bool HAL_adc_finished();
uint16_t analogRead(int adc_pin) { uint16_t analogRead(uint8_t adc_pin) {
HAL_adc_start_conversion(adc_pin); HAL_adc_start_conversion(adc_pin);
while (!HAL_adc_finished()); // Wait for conversion to finish while (!HAL_adc_finished()); // Wait for conversion to finish
return HAL_adc_get_result(); return HAL_adc_get_result();

View file

@ -92,18 +92,18 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
// Time functions // Time functions
extern "C" { extern "C" {
void delay(int milis); void delay(const int milis);
} }
void _delay_ms(int delay); void _delay_ms(const int delay);
void delayMicroseconds(unsigned long); void delayMicroseconds(unsigned long);
uint32_t millis(); uint32_t millis();
//IO functions //IO functions
void pinMode(int pin_number, int mode); void pinMode(uint8_t, uint8_t);
void digitalWrite(int pin_number, int pin_status); void digitalWrite(uint8_t, uint8_t);
bool digitalRead(int pin); int digitalRead(uint8_t);
void analogWrite(int pin_number, int pin_status); void analogWrite(uint8_t, int);
uint16_t analogRead(int adc_pin); int analogRead(uint8_t);
// EEPROM // EEPROM
void eeprom_write_byte(unsigned char *pos, unsigned char value); void eeprom_write_byte(unsigned char *pos, unsigned char value);

View file

@ -33,5 +33,5 @@
#else #else
#error Unsupported Platform! #error Unsupported Platform!
#endif #endif
#endif #endif

View file

@ -1,20 +1,18 @@
#if defined(__MK64FX512__) || defined(__MK66FX1M0__) #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "HAL_Servo_Teensy.h" #include "HAL_Servo_Teensy.h"
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
int8_t libServo::attach(const int pin) {
int8_t libServo::attach(int pin) { if (this->servoIndex >= MAX_SERVOS) return -1;
if (this->servoIndex >= MAX_SERVOS) return -1; return Servo::attach(pin);
return Servo::attach(pin);
} }
int8_t libServo::attach(int pin, int min, int max) { int8_t libServo::attach(const int pin, const int min, const int max) {
return Servo::attach(pin, min, max); return Servo::attach(pin, min, max);
} }
void libServo::move(int value) { void libServo::move(const int value) {
if (this->attach(0) >= 0) { if (this->attach(0) >= 0) {
this->write(value); this->write(value);
delay(SERVO_DELAY); delay(SERVO_DELAY);
@ -24,5 +22,4 @@ void libServo::move(int value) {
} }
} }
#endif // __MK64FX512__ || __MK66FX1M0__
#endif

View file

@ -6,13 +6,13 @@
// Inherit and expand on the official library // Inherit and expand on the official library
class libServo : public Servo { class libServo : public Servo {
public: public:
int8_t attach(int pin); int8_t attach(const int pin);
int8_t attach(int pin, int min, int max); int8_t attach(const int pin, const int min, const int max);
void move(int value); void move(const int value);
private: private:
uint16_t min_ticks; uint16_t min_ticks;
uint16_t max_ticks; uint16_t max_ticks;
uint8_t servoIndex; // index into the channel data for this servo uint8_t servoIndex; // index into the channel data for this servo
}; };
#endif #endif // HAL_Servo_Teensy_h

View file

@ -1,9 +1,9 @@
/* ************************************************************************** /* **************************************************************************
Marlin 3D Printer Firmware Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
This program is free software: you can redistribute it and/or modify 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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or

View file

@ -1,5 +1,5 @@
/* ************************************************************************** /* **************************************************************************
Marlin 3D Printer Firmware Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
@ -122,7 +122,7 @@ void HAL_adc_init();
#define HAL_ANALOG_SELECT(pin) NOOP; #define HAL_ANALOG_SELECT(pin) NOOP;
void HAL_adc_start_conversion(uint8_t adc_pin); void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void); uint16_t HAL_adc_get_result(void);

View file

@ -50,8 +50,8 @@
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20)) #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20))
void HAL_print_analog_pin(char buffer[], int8_t pin) { void HAL_print_analog_pin(char buffer[], int8_t pin) {
if (pin <= 23) sprintf(buffer, "(A%2d) ", int(pin - 14)); if (pin <= 23) sprintf(buffer, "(A%2d) ", int(pin - 14));
else if (pin <= 39) sprintf(buffer, "(A%2d) ", int(pin - 19)); else if (pin <= 39) sprintf(buffer, "(A%2d) ", int(pin - 19));
} }
void HAL_analog_pin_state(char buffer[], int8_t pin) { void HAL_analog_pin_state(char buffer[], int8_t pin) {

View file

@ -33,20 +33,20 @@ void spiBegin(void) {
/** Configure SPI for specified SPI speed */ /** Configure SPI for specified SPI speed */
void spiInit(uint8_t spiRate) { void spiInit(uint8_t spiRate) {
// Use datarates Marlin uses // Use datarates Marlin uses
uint32_t clock; uint32_t clock;
switch (spiRate) { switch (spiRate) {
case SPI_FULL_SPEED: clock = 10000000; break; case SPI_FULL_SPEED: clock = 10000000; break;
case SPI_HALF_SPEED: clock = 5000000; break; case SPI_HALF_SPEED: clock = 5000000; break;
case SPI_QUARTER_SPEED: clock = 2500000; break; case SPI_QUARTER_SPEED: clock = 2500000; break;
case SPI_EIGHTH_SPEED: clock = 1250000; break; case SPI_EIGHTH_SPEED: clock = 1250000; break;
case SPI_SPEED_5: clock = 625000; break; case SPI_SPEED_5: clock = 625000; break;
case SPI_SPEED_6: clock = 312500; break; case SPI_SPEED_6: clock = 312500; break;
default: default:
clock = 4000000; // Default from the SPI libarary clock = 4000000; // Default from the SPI libarary
} }
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
SPI.begin(); SPI.begin();
} }
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------

View file

@ -1,9 +1,9 @@
/* ************************************************************************** /* **************************************************************************
Marlin 3D Printer Firmware Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
This program is free software: you can redistribute it and/or modify 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 it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or

View file

@ -1,5 +1,5 @@
/* ************************************************************************** /* **************************************************************************
Marlin 3D Printer Firmware Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com

View file

@ -21,20 +21,13 @@
*/ */
/** /**
This code contributed by Triffid_Hunter and modified by Kliment * Fast I/O Routines for Teensy 3.5 and Teensy 3.6
why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html * Use direct port manipulation to save scads of processor time.
*/ * Contributed by Triffid_Hunter. Modified by Kliment and the Marlin team.
/**
* Description: Fast IO functions for Teensy 3.5 and Teensy 3.6
*/ */
#ifndef _FASTIO_TEENSY_H #ifndef _FASTIO_TEENSY_H
#define _FASTIO_TEENSY_H #define _FASTIO_TEENSY_H
/**
utility functions
*/
#ifndef MASK #ifndef MASK
#define MASK(PIN) (1 << PIN) #define MASK(PIN) (1 << PIN)
@ -44,77 +37,50 @@
#define GPIO_BITBAND(reg, bit) (*(uint32_t *)GPIO_BITBAND_ADDR((reg), (bit))) #define GPIO_BITBAND(reg, bit) (*(uint32_t *)GPIO_BITBAND_ADDR((reg), (bit)))
/** /**
magic I/O routines * Magic I/O routines
now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0); *
*/ * Now you can simply SET_OUTPUT(PIN); WRITE(PIN, HIGH); WRITE(PIN, LOW);
*
* Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
*/
/// Read a pin
#define _READ(p) ((bool)(CORE_PIN ## p ## _PINREG & CORE_PIN ## p ## _BITMASK)) #define _READ(p) ((bool)(CORE_PIN ## p ## _PINREG & CORE_PIN ## p ## _BITMASK))
/// Write to a pin
#define _WRITE(p, v) do { if (v) CORE_PIN ## p ## _PORTSET = CORE_PIN ## p ## _BITMASK; \ #define _WRITE(p, v) do { if (v) CORE_PIN ## p ## _PORTSET = CORE_PIN ## p ## _BITMASK; \
else CORE_PIN ## p ## _PORTCLEAR = CORE_PIN ## p ## _BITMASK; } while (0) else CORE_PIN ## p ## _PORTCLEAR = CORE_PIN ## p ## _BITMASK; } while (0)
/// toggle a pin
#define _TOGGLE(p) (*(&(CORE_PIN ## p ## _PORTCLEAR)+1) = CORE_PIN ## p ## _BITMASK) #define _TOGGLE(p) (*(&(CORE_PIN ## p ## _PORTCLEAR)+1) = CORE_PIN ## p ## _BITMASK)
#define _SET_INPUT(p) do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1); \
GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 0; \
} while (0)
#define _SET_OUTPUT(p) do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1)|PORT_PCR_SRE|PORT_PCR_DSE; \
GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 1; \
} while (0)
/// set pin as input
#define _SET_INPUT(p) do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1); \
GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 0; \
} while (0)
/// set pin as output
#define _SET_OUTPUT(p) do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1)|PORT_PCR_SRE|PORT_PCR_DSE; \
GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 1; \
} while (0)
/// set pin as input with pullup mode
//#define _PULLUP(IO, v) { pinMode(IO, (v!=LOW ? INPUT_PULLUP : INPUT)); } //#define _PULLUP(IO, v) { pinMode(IO, (v!=LOW ? INPUT_PULLUP : INPUT)); }
/// check if pin is an input
#define _GET_INPUT(p) ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0) #define _GET_INPUT(p) ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0)
/// check if pin is an output
#define _GET_OUTPUT(p) ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0) #define _GET_OUTPUT(p) ((CORE_PIN ## p ## _DDRREG & CORE_PIN ## p ## _BITMASK) == 0)
/// check if pin is an timer
//#define _GET_TIMER(IO) //#define _GET_TIMER(IO)
// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
/// Read a pin wrapper
#define READ(IO) _READ(IO) #define READ(IO) _READ(IO)
/// Write to a pin wrapper
#define WRITE_VAR(IO, v) _WRITE_VAR(IO, v) #define WRITE_VAR(IO, v) _WRITE_VAR(IO, v)
#define WRITE(IO, v) _WRITE(IO, v) #define WRITE(IO, v) _WRITE(IO, v)
/// toggle a pin wrapper
#define TOGGLE(IO) _TOGGLE(IO) #define TOGGLE(IO) _TOGGLE(IO)
/// set pin as input wrapper
#define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT(IO) _SET_INPUT(IO)
/// set pin as input with pullup wrapper
#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0) #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0)
/// set pin as output wrapper
#define SET_OUTPUT(IO) _SET_OUTPUT(IO) #define SET_OUTPUT(IO) _SET_OUTPUT(IO)
/// check if pin is an input wrapper
#define GET_INPUT(IO) _GET_INPUT(IO) #define GET_INPUT(IO) _GET_INPUT(IO)
/// check if pin is an output wrapper
#define GET_OUTPUT(IO) _GET_OUTPUT(IO) #define GET_OUTPUT(IO) _GET_OUTPUT(IO)
// Shorthand
#define OUT_WRITE(IO, v) { SET_OUTPUT(IO); WRITE(IO, v); } #define OUT_WRITE(IO, v) { SET_OUTPUT(IO); WRITE(IO, v); }
/** /**
ports and functions * Ports, functions, and pins
*/
added as necessary or if I feel like it- not a comprehensive list!
*/
/**
pins
*/
#define DIO0_PIN 8 #define DIO0_PIN 8
#endif /* _FASTIO_TEENSY_H */ #endif /* _FASTIO_TEENSY_H */

View file

@ -23,9 +23,9 @@
#ifndef SPI_PINS_H_ #ifndef SPI_PINS_H_
#define SPI_PINS_H_ #define SPI_PINS_H_
#define SCK_PIN 13 #define SCK_PIN 13
#define MISO_PIN 12 #define MISO_PIN 12
#define MOSI_PIN 11 #define MOSI_PIN 11
#define SS_PIN 20 //SDSS // A.28, A.29, B.21, C.26, C.29 #define SS_PIN 20 //SDSS // A.28, A.29, B.21, C.26, C.29
#endif /* SPI_PINS_H_ */ #endif /* SPI_PINS_H_ */

View file

@ -21,19 +21,19 @@
*/ */
#if defined(__MK64FX512__) || defined(__MK66FX1M0__) #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../../Marlin.h"
#if ENABLED(USE_WATCHDOG) #include "../../inc/MarlinConfig.h"
#include "watchdog_Teensy.h" #if ENABLED(USE_WATCHDOG)
void watchdog_init() { #include "watchdog_Teensy.h"
WDOG_TOVALH = 0;
WDOG_TOVALL = 4000;
WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
}
#endif //USE_WATCHDOG void watchdog_init() {
WDOG_TOVALH = 0;
WDOG_TOVALL = 4000;
WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
}
#endif #endif // USE_WATCHDOG
#endif // __MK64FX512__ || __MK66FX1M0__

View file

@ -1392,9 +1392,9 @@
#define MAX7219_DEBUG #define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG) #if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display #define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM #define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM #define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
/** /**
* Sample debug features * Sample debug features

View file

@ -26,7 +26,7 @@
uint8_t case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS; uint8_t case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS;
bool case_light_on = CASE_LIGHT_DEFAULT_ON; bool case_light_on = CASE_LIGHT_DEFAULT_ON;
#ifndef INVERT_CASE_LIGHT #ifndef INVERT_CASE_LIGHT
#define INVERT_CASE_LIGHT false #define INVERT_CASE_LIGHT false
#endif #endif

View file

@ -74,7 +74,7 @@ void dac084s085::setValue(uint8_t channel, uint8_t value) {
externalDac_buf[0] |= (value >> 4); externalDac_buf[0] |= (value >> 4);
externalDac_buf[1] |= (value << 4); externalDac_buf[1] |= (value << 4);
// All SPI chip-select HIGH // All SPI chip-select HIGH
digitalWrite( DAC0_SYNC , HIGH ); digitalWrite( DAC0_SYNC , HIGH );
#if EXTRUDERS > 1 #if EXTRUDERS > 1

View file

@ -375,7 +375,7 @@ void GcodeSuite::G33() {
float a_sum = 0.0; float a_sum = 0.0;
LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis]; LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis];
LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0; LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0;
// adjust delta_height and endstops by the max amount // adjust delta_height and endstops by the max amount
const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]); const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
home_offset[Z_AXIS] -= z_temp; home_offset[Z_AXIS] -= z_temp;

View file

@ -142,13 +142,13 @@ uint8_t u8g_dev_st7565_64128n_2x_VIKI_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg
ST7565_WRITE_BYTE(0x40); // Display start line for Displaytech 64128N ST7565_WRITE_BYTE(0x40); // Display start line for Displaytech 64128N
ST7565_WRITE_BYTE(0x28 | 0x04); // power control: turn on voltage converter ST7565_WRITE_BYTE(0x28 | 0x04); // power control: turn on voltage converter
//U8G_ESC_DLY(50); // delay 50 ms - hangs after a reset if used //U8G_ESC_DLY(50); // delay 50 ms - hangs after a reset if used
ST7565_WRITE_BYTE(0x28 | 0x06); // power control: turn on voltage regulator ST7565_WRITE_BYTE(0x28 | 0x06); // power control: turn on voltage regulator
//U8G_ESC_DLY(50); // delay 50 ms - hangs after a reset if used //U8G_ESC_DLY(50); // delay 50 ms - hangs after a reset if used
ST7565_WRITE_BYTE(0x28 | 0x07); // power control: turn on voltage follower ST7565_WRITE_BYTE(0x28 | 0x07); // power control: turn on voltage follower
//U8G_ESC_DLY(50); // delay 50 ms - hangs after a reset if used //U8G_ESC_DLY(50); // delay 50 ms - hangs after a reset if used
ST7565_WRITE_BYTE(0x10); // Set V0 voltage resistor ratio. Setting for controlling brightness of Displaytech 64128N ST7565_WRITE_BYTE(0x10); // Set V0 voltage resistor ratio. Setting for controlling brightness of Displaytech 64128N
@ -228,12 +228,12 @@ u8g_dev_t u8g_dev_st7565_64128n_2x_VIKI_sw_spi = { u8g_dev_st7565_64128n_2x_VIKI
class U8GLIB_ST7565_64128n_2x_VIKI : public U8GLIB { class U8GLIB_ST7565_64128n_2x_VIKI : public U8GLIB {
public: public:
U8GLIB_ST7565_64128n_2x_VIKI(uint8_t dummy) U8GLIB_ST7565_64128n_2x_VIKI(uint8_t dummy)
: U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi) : U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi)
{ }
U8GLIB_ST7565_64128n_2x_VIKI(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE)
: U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi)
{ } { }
U8GLIB_ST7565_64128n_2x_VIKI(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE)
: U8GLIB(&u8g_dev_st7565_64128n_2x_VIKI_sw_spi)
{ }
}; };
#pragma GCC reset_options #pragma GCC reset_options

View file

@ -176,9 +176,9 @@
//U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes //U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes
U8GLIB_LM6059_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes U8GLIB_LM6059_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes
#elif ENABLED(U8GLIB_ST7565_64128N) #elif ENABLED(U8GLIB_ST7565_64128N)
// The MaKrPanel, Mini Viki, and Viki 2.0, ST7565 controller // The MaKrPanel, Mini Viki, and Viki 2.0, ST7565 controller
//U8GLIB_ST7565_64128n_2x_VIKI u8g(0); // using SW-SPI DOGLCD_MOSI != -1 && DOGLCD_SCK //U8GLIB_ST7565_64128n_2x_VIKI u8g(0); // using SW-SPI DOGLCD_MOSI != -1 && DOGLCD_SCK
U8GLIB_ST7565_64128n_2x_VIKI u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0); // using SW-SPI U8GLIB_ST7565_64128n_2x_VIKI u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0); // using SW-SPI
//U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes //U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes
//U8GLIB_NHD_C12864_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes HWSPI //U8GLIB_NHD_C12864_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes HWSPI
#elif ENABLED(U8GLIB_SSD1306) #elif ENABLED(U8GLIB_SSD1306)

View file

@ -302,7 +302,7 @@ class Stepper {
#endif #endif
#ifdef CPU_32_BIT #ifdef CPU_32_BIT
// In case of high-performance processor, it is able to calculate in real-time // In case of high-performance processor, it is able to calculate in real-time
timer = (uint32_t)(HAL_STEPPER_TIMER_RATE) / step_rate; timer = (uint32_t)(HAL_STEPPER_TIMER_RATE) / step_rate;
if (timer < (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2))) { // (STEP_DOUBLER_FREQUENCY * 2 kHz - this should never happen) if (timer < (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2))) { // (STEP_DOUBLER_FREQUENCY * 2 kHz - this should never happen)
timer = (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2)); timer = (HAL_STEPPER_TIMER_RATE / (STEP_DOUBLER_FREQUENCY * 2));

View file

@ -45,7 +45,7 @@
#define IS_RAMPS_EFF #define IS_RAMPS_EFF
#elif MB(RAMPS_13_EEF) || MB(RAMPS_14_EEF) || MB(RAMPS_14_RE_ARM_EEF) || MB(RAMPS_SMART_EEF) || MB(RAMPS_DUO_EEF) || MB(RAMPS4DUE_EEF) #elif MB(RAMPS_13_EEF) || MB(RAMPS_14_EEF) || MB(RAMPS_14_RE_ARM_EEF) || MB(RAMPS_SMART_EEF) || MB(RAMPS_DUO_EEF) || MB(RAMPS4DUE_EEF)
#define IS_RAMPS_EEF #define IS_RAMPS_EEF
#elif MB(RAMPS_13_SF) || MB(RAMPS_14_SF) || MB(RAMPS_14_RE_ARM_SF) || MB(RAMPS_SMART_SF) || MB(RAMPS_DUO_SF) || MB(RAMPS4DUE_SF) #elif MB(RAMPS_13_SF) || MB(RAMPS_14_SF) || MB(RAMPS_14_RE_ARM_SF) || MB(RAMPS_SMART_SF) || MB(RAMPS_DUO_SF) || MB(RAMPS4DUE_SF)
#define IS_RAMPS_SF #define IS_RAMPS_SF
#endif #endif

View file

@ -358,7 +358,7 @@
#endif #endif
#if PIN_EXISTS(FAN) #if PIN_EXISTS(FAN)
REPORT_NAME_DIGITAL(FAN_PIN, __LINE__ ) REPORT_NAME_DIGITAL(FAN_PIN, __LINE__ )
#endif #endif
#if PIN_EXISTS(FAN1) #if PIN_EXISTS(FAN1)
REPORT_NAME_DIGITAL(FAN1_PIN, __LINE__ ) REPORT_NAME_DIGITAL(FAN1_PIN, __LINE__ )
#endif #endif

View file

@ -123,7 +123,7 @@
#define BTN_EN1 50 #define BTN_EN1 50
#define BTN_EN2 52 #define BTN_EN2 52
#define BTN_ENC 48 #define BTN_ENC 48
#define SDSS 4 #define SDSS 4
#define SD_DETECT_PIN 14 #define SD_DETECT_PIN 14
@ -135,9 +135,9 @@
#define BTN_EN1 50 #define BTN_EN1 50
#define BTN_EN2 52 #define BTN_EN2 52
#define BTN_ENC 48 #define BTN_ENC 48
#define BTN_BACK 71 #define BTN_BACK 71
#undef SDSS #undef SDSS
#define SDSS 4 #define SDSS 4
#define SD_DETECT_PIN 14 #define SD_DETECT_PIN 14

View file

@ -115,7 +115,7 @@
#define BTN_EN1 50 #define BTN_EN1 50
#define BTN_EN2 52 #define BTN_EN2 52
#define BTN_ENC 48 #define BTN_ENC 48
#define SDSS 4 #define SDSS 4
#define SD_DETECT_PIN 14 #define SD_DETECT_PIN 14
@ -127,9 +127,9 @@
#define BTN_EN1 50 #define BTN_EN1 50
#define BTN_EN2 52 #define BTN_EN2 52
#define BTN_ENC 48 #define BTN_ENC 48
#define BTN_BACK 71 #define BTN_BACK 71
#undef SDSS #undef SDSS
#define SDSS 4 #define SDSS 4
#define SD_DETECT_PIN 14 #define SD_DETECT_PIN 14

View file

@ -46,8 +46,8 @@
#if ENABLED(IS_REARM) #if ENABLED(IS_REARM)
#error "Oops! use 'pins_RAMPS_RE_ARM.h' when Re-Arm is used." #error "Oops! use 'pins_RAMPS_RE_ARM.h' when Re-Arm is used."
#endif #endif
#if !ENABLED(IS_RAMPS_SMART) && !ENABLED(IS_RAMPS_DUO) && !ENABLED(IS_RAMPS4DUE) && !ENABLED(TARGET_LPC1768) #if !ENABLED(IS_RAMPS_SMART) && !ENABLED(IS_RAMPS_DUO) && !ENABLED(IS_RAMPS4DUE) && !ENABLED(TARGET_LPC1768)
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
#error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu."

View file

@ -248,12 +248,12 @@
#define DOGLCD_CS 63 // J5-3 & AUX-2 #define DOGLCD_CS 63 // J5-3 & AUX-2
#ifdef ULTIPANEL #ifdef ULTIPANEL
#define LCD_PINS_D5 71 // ENET_MDIO #define LCD_PINS_D5 71 // ENET_MDIO
#define LCD_PINS_D6 73 // ENET_RX_ER #define LCD_PINS_D6 73 // ENET_RX_ER
#define LCD_PINS_D7 75 // ENET_RXD1 #define LCD_PINS_D7 75 // ENET_RXD1
#endif #endif
#if ENABLED(NEWPANEL) #if ENABLED(NEWPANEL)
#if ENABLED(REPRAPWORLD_KEYPAD) #if ENABLED(REPRAPWORLD_KEYPAD)
#define SHIFT_OUT 51 // (MOSI) J3-10 & AUX-3 #define SHIFT_OUT 51 // (MOSI) J3-10 & AUX-3
@ -287,12 +287,12 @@
#if ENABLED(VIKI2) || ENABLED(miniVIKI) #if ENABLED(VIKI2) || ENABLED(miniVIKI)
// #define LCD_SCREEN_ROT_180 // #define LCD_SCREEN_ROT_180
#define SOFTWARE_SPI // temp to see if it fixes the "not found" error #define SOFTWARE_SPI // temp to see if it fixes the "not found" error
#undef BEEPER_PIN #undef BEEPER_PIN
#define BEEPER_PIN 37 // may change if cable changes #define BEEPER_PIN 37 // may change if cable changes
#define BTN_EN1 31 // J3-2 & AUX-4 #define BTN_EN1 31 // J3-2 & AUX-4
#define BTN_EN2 33 // J3-4 & AUX-4 #define BTN_EN2 33 // J3-4 & AUX-4
#define BTN_ENC 35 // J3-3 & AUX-4 #define BTN_ENC 35 // J3-3 & AUX-4
@ -301,7 +301,7 @@
#define KILL_PIN 41 // J5-4 & AUX-4 #define KILL_PIN 41 // J5-4 & AUX-4
#undef DOGLCD_CS #undef DOGLCD_CS
#define DOGLCD_CS 16 #define DOGLCD_CS 16
#undef LCD_BACKLIGHT_PIN //16 // J3-7 & AUX-4 - only used on DOGLCD controllers #undef LCD_BACKLIGHT_PIN //16 // J3-7 & AUX-4 - only used on DOGLCD controllers
#undef LCD_PINS_ENABLE //51 // (MOSI) J3-10 & AUX-3 #undef LCD_PINS_ENABLE //51 // (MOSI) J3-10 & AUX-3
#undef LCD_PINS_D4 //52 // (SCK) J3-9 & AUX-3 #undef LCD_PINS_D4 //52 // (SCK) J3-9 & AUX-3
@ -310,9 +310,9 @@
#define DOGLCD_A0 59 // J3-8 & AUX-2 #define DOGLCD_A0 59 // J3-8 & AUX-2
#undef LCD_PINS_D6 //63 // J5-3 & AUX-2 #undef LCD_PINS_D6 //63 // J5-3 & AUX-2
#undef LCD_PINS_D7 //6 // (SERVO1) J5-1 & SERVO connector #undef LCD_PINS_D7 //6 // (SERVO1) J5-1 & SERVO connector
#define DOGLCD_SCK SCK_PIN #define DOGLCD_SCK SCK_PIN
#define DOGLCD_MOSI MOSI_PIN #define DOGLCD_MOSI MOSI_PIN
#define STAT_LED_BLUE_PIN 63 // may change if cable changes #define STAT_LED_BLUE_PIN 63 // may change if cable changes
#define STAT_LED_RED_PIN 6 // may change if cable changes #define STAT_LED_RED_PIN 6 // may change if cable changes
#endif #endif
@ -320,8 +320,8 @@
//#define MOSI_PIN 51 // system defined J3-10 & AUX-3 //#define MOSI_PIN 51 // system defined J3-10 & AUX-3
//#define SCK_PIN 52 // system defined J3-9 & AUX-3 //#define SCK_PIN 52 // system defined J3-9 & AUX-3
//#define SS_PIN 53 // system defined J3-5 & AUX-3 - sometimes called SDSS //#define SS_PIN 53 // system defined J3-5 & AUX-3 - sometimes called SDSS
#if ENABLED(MINIPANEL) #if ENABLED(MINIPANEL)
// GLCD features // GLCD features
//#define LCD_CONTRAST 190 //#define LCD_CONTRAST 190

View file

@ -2,7 +2,7 @@
* Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0) Breadboard pin assignments * Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0) Breadboard pin assignments
* Requires the Teensyduino software with Teensy 3.5 or Teensy 3.6 selected in Arduino IDE! * Requires the Teensyduino software with Teensy 3.5 or Teensy 3.6 selected in Arduino IDE!
* http://www.pjrc.com/teensy/teensyduino.html * http://www.pjrc.com/teensy/teensyduino.html
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 841 // BOARD_TEENSY35_36 #if MOTHERBOARD == 841 // BOARD_TEENSY35_36
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
@ -21,7 +21,7 @@
#define LARGE_FLASH true #define LARGE_FLASH true
#define USBCON //1286 // Disable MarlinSerial etc. #define USBCON //1286 // Disable MarlinSerial etc.
/* /*
teemuatlut plan for Teensy3.5 and Teensy3.6: teemuatlut plan for Teensy3.5 and Teensy3.6:
USB USB
@ -109,22 +109,22 @@ D8 HEATER_BED_PIN CS1 RX4 A12 31 | 46 * * 47 | 34 A15 PWM
#define SOL1_PIN 28 #define SOL1_PIN 28
#ifndef SDSUPPORT #ifndef SDSUPPORT
// these pins are defined in the SD library if building with SD support // these are defined in the SD library if building with SD support
#define SCK_PIN 13 #define SCK_PIN 13
#define MISO_PIN 12 #define MISO_PIN 12
#define MOSI_PIN 11 #define MOSI_PIN 11
#endif #endif
#ifdef ULTRA_LCD #ifdef ULTRA_LCD
#define LCD_PINS_RS 40 #define LCD_PINS_RS 40
#define LCD_PINS_ENABLE 41 #define LCD_PINS_ENABLE 41
#define LCD_PINS_D4 42 #define LCD_PINS_D4 42
#define LCD_PINS_D5 43 #define LCD_PINS_D5 43
#define LCD_PINS_D6 44 #define LCD_PINS_D6 44
#define LCD_PINS_D7 45 #define LCD_PINS_D7 45
#define BTN_EN1 46 #define BTN_EN1 46
#define BTN_EN2 47 #define BTN_EN2 47
#define BTN_ENC 48 #define BTN_ENC 48
#endif #endif
#endif // MOTHERBOARD == 841 (Teensy3.5 and Teensy3.6) #endif // MOTHERBOARD == 841 (Teensy3.5 and Teensy3.6)

View file

@ -1,13 +1,13 @@
/* File: startup_ARMCM3.s /* File: startup_ARMCM3.s
* Purpose: startup file for Cortex-M3/M4 devices. Should use with * Purpose: startup file for Cortex-M3/M4 devices. Should use with
* GNU Tools for ARM Embedded Processors * GNU Tools for ARM Embedded Processors
* Version: V1.1 * Version: V1.1
* Date: 17 June 2011 * Date: 17 June 2011
* *
* Copyright (C) 2011 ARM Limited. All rights reserved. * Copyright (C) 2011 ARM Limited. All rights reserved.
* ARM Limited (ARM) is supplying this software for use with Cortex-M3/M4 * ARM Limited (ARM) is supplying this software for use with Cortex-M3/M4
* processor based microcontrollers. This file can be freely distributed * processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors. * within development tools that are supporting such ARM based processors.
* *
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
@ -20,12 +20,12 @@
/* Memory Model /* Memory Model
The HEAP starts at the end of the DATA section and grows upward. The HEAP starts at the end of the DATA section and grows upward.
The STACK starts at the end of the RAM and grows downward. The STACK starts at the end of the RAM and grows downward.
The HEAP and stack STACK are only checked at compile time: The HEAP and stack STACK are only checked at compile time:
(DATA_SIZE + HEAP_SIZE + STACK_SIZE) < RAM_SIZE (DATA_SIZE + HEAP_SIZE + STACK_SIZE) < RAM_SIZE
This is just a check for the bare minimum for the Heap+Stack area before This is just a check for the bare minimum for the Heap+Stack area before
aborting compilation, it is not the run time limit: aborting compilation, it is not the run time limit:
Heap_Size + Stack_Size = 0x80 + 0x80 = 0x100 Heap_Size + Stack_Size = 0x80 + 0x80 = 0x100
@ -59,7 +59,7 @@ __HeapBase:
.size __HeapBase, . - __HeapBase .size __HeapBase, . - __HeapBase
__HeapLimit: __HeapLimit:
.size __HeapLimit, . - __HeapLimit .size __HeapLimit, . - __HeapLimit
.section .isr_vector .section .isr_vector
.align 2 .align 2
.globl __isr_vector .globl __isr_vector
@ -128,7 +128,7 @@ __isr_vector:
.type Reset_Handler, %function .type Reset_Handler, %function
Reset_Handler: Reset_Handler:
/* Loop to copy data from read only memory to RAM. The ranges /* Loop to copy data from read only memory to RAM. The ranges
* of copy from/to are specified by following symbols evaluated in * of copy from/to are specified by following symbols evaluated in
* linker script. * linker script.
* _etext: End of code section, i.e., begin of data sections to copy from. * _etext: End of code section, i.e., begin of data sections to copy from.
* __data_start__/__data_end__: RAM address range that data should be * __data_start__/__data_end__: RAM address range that data should be
@ -153,7 +153,7 @@ Reset_Handler:
bx r0 bx r0
.pool .pool
.size Reset_Handler, . - Reset_Handler .size Reset_Handler, . - Reset_Handler
/* Macro to define default handlers. Default handler /* Macro to define default handlers. Default handler
* will be weak symbol and just dead loops. They can be * will be weak symbol and just dead loops. They can be
* overwritten by other handlers */ * overwritten by other handlers */
@ -166,7 +166,7 @@ Reset_Handler:
b . b .
.size \handler_name, . - \handler_name .size \handler_name, . - \handler_name
.endm .endm
def_default_handler NMI_Handler def_default_handler NMI_Handler
def_default_handler HardFault_Handler def_default_handler HardFault_Handler
def_default_handler MemManage_Handler def_default_handler MemManage_Handler
@ -177,7 +177,7 @@ Reset_Handler:
def_default_handler PendSV_Handler def_default_handler PendSV_Handler
def_default_handler SysTick_Handler def_default_handler SysTick_Handler
def_default_handler Default_Handler def_default_handler Default_Handler
def_default_handler WDT_IRQHandler def_default_handler WDT_IRQHandler
def_default_handler TIMER0_IRQHandler def_default_handler TIMER0_IRQHandler
def_default_handler TIMER1_IRQHandler def_default_handler TIMER1_IRQHandler

View file

@ -188,7 +188,7 @@ static uint32_t I2C_SendByte (LPC_I2C_TypeDef *I2Cx, uint8_t databyte)
{ {
return CodeStatus; return CodeStatus;
} }
/* Make sure start bit is not active */ /* Make sure start bit is not active */
if (I2Cx->I2CONSET & I2C_I2CONSET_STA) if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
{ {
@ -216,7 +216,7 @@ static uint32_t I2C_SendByte (LPC_I2C_TypeDef *I2Cx, uint8_t databyte)
static uint32_t I2C_GetByte (LPC_I2C_TypeDef *I2Cx, uint8_t *retdat, Bool ack) static uint32_t I2C_GetByte (LPC_I2C_TypeDef *I2Cx, uint8_t *retdat, Bool ack)
{ {
*retdat = (uint8_t) (I2Cx->I2DAT & I2C_I2DAT_BITMASK); *retdat = (uint8_t) (I2Cx->I2DAT & I2C_I2DAT_BITMASK);
if (ack == TRUE) if (ack == TRUE)
{ {
I2Cx->I2CONSET = I2C_I2CONSET_AA; I2Cx->I2CONSET = I2C_I2CONSET_AA;
@ -227,7 +227,7 @@ static uint32_t I2C_GetByte (LPC_I2C_TypeDef *I2Cx, uint8_t *retdat, Bool ack)
} }
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC; I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK); return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
} }
@ -454,7 +454,7 @@ int32_t I2C_MasterHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_M
uint8_t *rxdat; uint8_t *rxdat;
uint8_t tmp; uint8_t tmp;
int32_t Ret = I2C_OK; int32_t Ret = I2C_OK;
//get buffer to send/receive //get buffer to send/receive
txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count]; txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count];
rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count]; rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count];
@ -481,11 +481,11 @@ int32_t I2C_MasterHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_M
break; break;
case I2C_I2STAT_M_TX_SLAW_ACK: case I2C_I2STAT_M_TX_SLAW_ACK:
case I2C_I2STAT_M_TX_DAT_ACK: case I2C_I2STAT_M_TX_DAT_ACK:
if(TransferCfg->tx_count < TransferCfg->tx_length) if(TransferCfg->tx_count < TransferCfg->tx_length)
{ {
I2C_SendByte(I2Cx, *txdat); I2C_SendByte(I2Cx, *txdat);
txdat++; txdat++;
TransferCfg->tx_count++; TransferCfg->tx_count++;
@ -497,7 +497,7 @@ int32_t I2C_MasterHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_M
I2C_Stop(I2Cx); I2C_Stop(I2Cx);
Ret = I2C_SEND_END; Ret = I2C_SEND_END;
} }
break; break;
case I2C_I2STAT_M_TX_DAT_NACK: case I2C_I2STAT_M_TX_DAT_NACK:
@ -537,7 +537,7 @@ int32_t I2C_MasterHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_M
{ {
Ret = I2C_RECV_END; Ret = I2C_RECV_END;
} }
break; break;
case I2C_I2STAT_M_RX_DAT_NACK: case I2C_I2STAT_M_RX_DAT_NACK:
I2C_GetByte(I2Cx, &tmp, FALSE); I2C_GetByte(I2Cx, &tmp, FALSE);
@ -559,7 +559,7 @@ int32_t I2C_MasterHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_M
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC; I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
break; break;
} }
return Ret; return Ret;
} }
@ -592,7 +592,7 @@ int32_t I2C_SlaveHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_S_
//get buffer to send/receive //get buffer to send/receive
txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count]; txdat = (uint8_t *) &TransferCfg->tx_data[TransferCfg->tx_count];
rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count]; rxdat = (uint8_t *) &TransferCfg->rx_data[TransferCfg->rx_count];
switch (CodeStatus) switch (CodeStatus)
{ {
/* Reading phase -------------------------------------------------------- */ /* Reading phase -------------------------------------------------------- */
@ -636,7 +636,7 @@ int32_t I2C_SlaveHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_S_
I2Cx->I2CONSET = I2C_I2CONSET_AA; I2Cx->I2CONSET = I2C_I2CONSET_AA;
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC; I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
} }
break; break;
/* DATA has been received, Only the first data byte will be received with ACK. Additional /* DATA has been received, Only the first data byte will be received with ACK. Additional
data will be received with NOT ACK. */ data will be received with NOT ACK. */
@ -688,7 +688,7 @@ int32_t I2C_SlaveHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_S_
I2Cx->I2CONSET = I2C_I2CONSET_AA|I2C_I2CONSET_STA; I2Cx->I2CONSET = I2C_I2CONSET_AA|I2C_I2CONSET_STA;
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC; I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
break; break;
case I2C_I2STAT_S_TX_LAST_DAT_ACK: case I2C_I2STAT_S_TX_LAST_DAT_ACK:
/* Data has been transmitted, NACK has been received, /* Data has been transmitted, NACK has been received,
* that means there's no more data to send, exit now */ * that means there's no more data to send, exit now */
@ -729,7 +729,7 @@ int32_t I2C_SlaveHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_S_
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC; I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
Ret = I2C_STA_STO_RECV; Ret = I2C_STA_STO_RECV;
break; break;
/* No status information */ /* No status information */
case I2C_I2STAT_NO_INF: case I2C_I2STAT_NO_INF:
/* Other status must be captured */ /* Other status must be captured */
@ -737,7 +737,7 @@ int32_t I2C_SlaveHanleStates(LPC_I2C_TypeDef *I2Cx, uint32_t CodeStatus, I2C_S_
I2Cx->I2CONSET = I2C_I2CONSET_AA; I2Cx->I2CONSET = I2C_I2CONSET_AA;
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC; I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
break; break;
} }
return Ret; return Ret;
@ -787,7 +787,7 @@ void I2C_MasterHandler(LPC_I2C_TypeDef *I2Cx)
else if (Ret & I2C_SEND_END) else if (Ret & I2C_SEND_END)
{ {
// If no need to wait for data from Slave // If no need to wait for data from Slave
if(txrx_setup->rx_count >= (txrx_setup->rx_length)) if(txrx_setup->rx_count >= (txrx_setup->rx_length))
{ {
goto s_int_end; goto s_int_end;
} }
@ -799,7 +799,7 @@ void I2C_MasterHandler(LPC_I2C_TypeDef *I2Cx)
return; return;
} }
} }
else if (Ret & I2C_RECV_END) else if (Ret & I2C_RECV_END)
{ {
goto s_int_end; goto s_int_end;
} }
@ -815,7 +815,7 @@ s_int_end:
I2Cx->I2CONCLR = I2C_I2CONCLR_AAC | I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC; I2Cx->I2CONCLR = I2C_I2CONCLR_AAC | I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC;
I2C_MasterComplete[i2cId] = TRUE; I2C_MasterComplete[i2cId] = TRUE;
} }
@ -874,7 +874,7 @@ handle_state:
goto s_int_end; goto s_int_end;
} }
} }
} }
} }
else if(Ret &I2C_SEND_END) else if(Ret &I2C_SEND_END)
{ {
@ -937,7 +937,7 @@ retry:
// Start command // Start command
CodeStatus = I2C_Start(I2Cx); CodeStatus = I2C_Start(I2Cx);
while(1) // send data first and then receive data from Slave. while(1) // send data first and then receive data from Slave.
{ {
Ret = I2C_MasterHanleStates(I2Cx, CodeStatus, TransferCfg); Ret = I2C_MasterHanleStates(I2Cx, CodeStatus, TransferCfg);
@ -955,13 +955,13 @@ retry:
else if( (Ret & I2C_BYTE_SENT) || else if( (Ret & I2C_BYTE_SENT) ||
(Ret & I2C_BYTE_RECV)) (Ret & I2C_BYTE_RECV))
{ {
// Wait for sending ends // Wait for sending ends
while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI)); while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
} }
else if (Ret & I2C_SEND_END) // already send all data else if (Ret & I2C_SEND_END) // already send all data
{ {
// If no need to wait for data from Slave // If no need to wait for data from Slave
if(TransferCfg->rx_count >= (TransferCfg->rx_length)) if(TransferCfg->rx_count >= (TransferCfg->rx_length))
{ {
break; break;
} }
@ -1037,7 +1037,7 @@ Status I2C_SlaveTransferData(LPC_I2C_TypeDef *I2Cx, I2C_S_SETUP_Type *TransferCf
I2C_TRANSFER_OPT_Type Opt) I2C_TRANSFER_OPT_Type Opt)
{ {
int32_t Ret = I2C_OK; int32_t Ret = I2C_OK;
uint32_t CodeStatus; uint32_t CodeStatus;
uint32_t timeout; uint32_t timeout;
int32_t time_en; int32_t time_en;
@ -1052,7 +1052,7 @@ Status I2C_SlaveTransferData(LPC_I2C_TypeDef *I2Cx, I2C_S_SETUP_Type *TransferCf
{ {
/* Set AA bit to ACK command on I2C bus */ /* Set AA bit to ACK command on I2C bus */
I2Cx->I2CONSET = I2C_I2CONSET_AA; I2Cx->I2CONSET = I2C_I2CONSET_AA;
/* Clear SI bit to be ready ... */ /* Clear SI bit to be ready ... */
I2Cx->I2CONCLR = (I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC|I2C_I2CONCLR_STOC); I2Cx->I2CONCLR = (I2C_I2CONCLR_SIC | I2C_I2CONCLR_STAC|I2C_I2CONCLR_STOC);

View file

@ -331,7 +331,7 @@ Status I2S_FreqConfig(LPC_I2S_TypeDef *I2Sx, uint32_t Freq, uint8_t TRMode) {
uint16_t dif; uint16_t dif;
uint16_t x_divide, y_divide; uint16_t x_divide, y_divide;
uint16_t err, ErrorOptimal = 0xFFFF; uint16_t err, ErrorOptimal = 0xFFFF;
uint32_t N; uint32_t N;
CHECK_PARAM(PARAM_I2Sx(I2Sx)); CHECK_PARAM(PARAM_I2Sx(I2Sx));
@ -360,7 +360,7 @@ Status I2S_FreqConfig(LPC_I2S_TypeDef *I2Sx, uint32_t Freq, uint8_t TRMode) {
* The formula is: * The formula is:
* I2S_MCLK = PCLK_I2S * (X/Y) / 2 * I2S_MCLK = PCLK_I2S * (X/Y) / 2
* In that, Y must be greater than or equal to X. X should divides evenly * In that, Y must be greater than or equal to X. X should divides evenly
* into Y. * into Y.
* We have: * We have:
* I2S_MCLK = Freq * channel*wordwidth * (I2STXBITRATE+1); * I2S_MCLK = Freq * channel*wordwidth * (I2STXBITRATE+1);
* So: (X/Y) = (Freq * channel*wordwidth * (I2STXBITRATE+1))*2/PCLK_I2S * So: (X/Y) = (Freq * channel*wordwidth * (I2STXBITRATE+1))*2/PCLK_I2S

View file

@ -1,35 +1,35 @@
/* ---------------------------------------------------------------------- /* ----------------------------------------------------------------------
* Copyright (C) 2010 ARM Limited. All rights reserved. * Copyright (C) 2010 ARM Limited. All rights reserved.
* *
* $Date: 11. November 2010 * $Date: 11. November 2010
* $Revision: V1.0.2 * $Revision: V1.0.2
* *
* Project: CMSIS DSP Library * Project: CMSIS DSP Library
* Title: arm_common_tables.h * Title: arm_common_tables.h
* *
* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions * Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions
* *
* Target Processor: Cortex-M4/Cortex-M3 * Target Processor: Cortex-M4/Cortex-M3
* *
* Version 1.0.2 2010/11/11 * Version 1.0.2 2010/11/11
* Documentation updated. * Documentation updated.
* *
* Version 1.0.1 2010/10/05 * Version 1.0.1 2010/10/05
* Production release and review comments incorporated. * Production release and review comments incorporated.
* *
* Version 1.0.0 2010/09/20 * Version 1.0.0 2010/09/20
* Production release and review comments incorporated. * Production release and review comments incorporated.
* -------------------------------------------------------------------- */ * -------------------------------------------------------------------- */
#ifndef _ARM_COMMON_TABLES_H #ifndef _ARM_COMMON_TABLES_H
#define _ARM_COMMON_TABLES_H #define _ARM_COMMON_TABLES_H
#include "arm_math.h" #include "arm_math.h"
extern uint16_t armBitRevTable[256]; extern uint16_t armBitRevTable[256];
extern q15_t armRecipTableQ15[64]; extern q15_t armRecipTableQ15[64];
extern q31_t armRecipTableQ31[64]; extern q31_t armRecipTableQ31[64];
extern const q31_t realCoefAQ31[1024]; extern const q31_t realCoefAQ31[1024];
extern const q31_t realCoefBQ31[1024]; extern const q31_t realCoefBQ31[1024];
#endif /* ARM_COMMON_TABLES_H */ #endif /* ARM_COMMON_TABLES_H */

View file

@ -8,9 +8,9 @@
* Copyright (C) 2009-2011 ARM Limited. All rights reserved. * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
* *
* @par * @par
* ARM Limited (ARM) is supplying this software for use with Cortex-M * ARM Limited (ARM) is supplying this software for use with Cortex-M
* processor based microcontrollers. This file can be freely distributed * processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors. * within development tools that are supporting such ARM based processors.
* *
* @par * @par
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
@ -26,7 +26,7 @@
/* ########################### Core Function Access ########################### */ /* ########################### Core Function Access ########################### */
/** \ingroup CMSIS_Core_FunctionInterface /** \ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
@{ @{
*/ */
@ -182,7 +182,7 @@ static __INLINE void __set_PRIMASK(uint32_t priMask)
register uint32_t __regPriMask __ASM("primask"); register uint32_t __regPriMask __ASM("primask");
__regPriMask = (priMask); __regPriMask = (priMask);
} }
#if (__CORTEX_M >= 0x03) #if (__CORTEX_M >= 0x03)
@ -226,7 +226,7 @@ static __INLINE void __set_BASEPRI(uint32_t basePri)
register uint32_t __regBasePri __ASM("basepri"); register uint32_t __regBasePri __ASM("basepri");
__regBasePri = (basePri & 0xff); __regBasePri = (basePri & 0xff);
} }
/** \brief Get Fault Mask /** \brief Get Fault Mask
@ -407,7 +407,7 @@ __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PSP(void)
__ASM volatile ("MRS %0, psp\n" : "=r" (result) ); __ASM volatile ("MRS %0, psp\n" : "=r" (result) );
return(result); return(result);
} }
/** \brief Set Process Stack Pointer /** \brief Set Process Stack Pointer
@ -434,7 +434,7 @@ __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_MSP(void)
__ASM volatile ("MRS %0, msp\n" : "=r" (result) ); __ASM volatile ("MRS %0, msp\n" : "=r" (result) );
return(result); return(result);
} }
/** \brief Set Main Stack Pointer /** \brief Set Main Stack Pointer
@ -473,7 +473,7 @@ __attribute__( ( always_inline ) ) static __INLINE void __set_PRIMASK(uint32_t p
{ {
__ASM volatile ("MSR primask, %0" : : "r" (priMask) ); __ASM volatile ("MSR primask, %0" : : "r" (priMask) );
} }
#if (__CORTEX_M >= 0x03) #if (__CORTEX_M >= 0x03)
@ -508,7 +508,7 @@ __attribute__( ( always_inline ) ) static __INLINE void __disable_fault_irq(void
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void) __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void)
{ {
uint32_t result; uint32_t result;
__ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); __ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
return(result); return(result);
} }
@ -535,7 +535,7 @@ __attribute__( ( always_inline ) ) static __INLINE void __set_BASEPRI(uint32_t v
__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void) __attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void)
{ {
uint32_t result; uint32_t result;
__ASM volatile ("MRS %0, faultmask" : "=r" (result) ); __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
return(result); return(result);
} }

View file

@ -7,7 +7,7 @@
* @version 1.0 * @version 1.0
* @date 18. April. 2012 * @date 18. April. 2012
* @author NXP MCU SW Application Team * @author NXP MCU SW Application Team
* *
* Copyright(C) 2011, NXP Semiconductor * Copyright(C) 2011, NXP Semiconductor
* All rights reserved. * All rights reserved.
* *
@ -112,7 +112,7 @@ typedef struct {
/** /**
* @} * @}
*/ */
/* Public Functions ----------------------------------------------------------- */ /* Public Functions ----------------------------------------------------------- */
/** @defgroup IAP_Public_Functions IAP Public Functions /** @defgroup IAP_Public_Functions IAP Public Functions
* @{ * @{
@ -128,7 +128,7 @@ IAP_STATUS_CODE CopyRAM2Flash(uint8_t * dest, uint8_t* source, IAP_WRITE_SIZE si
IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec); IAP_STATUS_CODE EraseSector(uint32_t start_sec, uint32_t end_sec);
/** Blank check sectors */ /** Blank check sectors */
IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec, IAP_STATUS_CODE BlankCheckSector(uint32_t start_sec, uint32_t end_sec,
uint32_t *first_nblank_loc, uint32_t *first_nblank_loc,
uint32_t *first_nblank_val); uint32_t *first_nblank_val);
/** Read part identification number */ /** Read part identification number */
IAP_STATUS_CODE ReadPartID(uint32_t *partID); IAP_STATUS_CODE ReadPartID(uint32_t *partID);

View file

@ -1,16 +1,16 @@
/****************************************************************************** /******************************************************************************
* @file: system_LPC17xx.h * @file: system_LPC17xx.h
* @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File * @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File
* for the NXP LPC17xx Device Series * for the NXP LPC17xx Device Series
* @version: V1.02 * @version: V1.02
* @date: 27. July 2009 * @date: 27. July 2009
*---------------------------------------------------------------------------- *----------------------------------------------------------------------------
* *
* Copyright (C) 2009 ARM Limited. All rights reserved. * Copyright (C) 2009 ARM Limited. All rights reserved.
* *
* ARM Limited (ARM) is supplying this software for use with Cortex-M3 * ARM Limited (ARM) is supplying this software for use with Cortex-M3
* processor based microcontrollers. This file can be freely distributed * processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors. * within development tools that are supporting such ARM based processors.
* *
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
@ -26,7 +26,7 @@
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
@ -48,7 +48,7 @@ extern void SystemInit (void);
* @param none * @param none
* @return none * @return none
* *
* @brief Updates the SystemCoreClock with current core Clock * @brief Updates the SystemCoreClock with current core Clock
* retrieved from cpu registers. * retrieved from cpu registers.
*/ */
extern void SystemCoreClockUpdate (void); extern void SystemCoreClockUpdate (void);

View file

@ -1,9 +1,9 @@
{ {
"name": "CMSIS-LPC1768", "name": "CMSIS-LPC1768",
"version": "0.0.0", "version": "0.0.0",
"frameworks": [], "frameworks": [],
"platforms": [ "platforms": [
"nxplpc", "nxplpc",
"ststm32" "ststm32"
], ],
"description": "CMSIS library for LPC1768", "description": "CMSIS library for LPC1768",