[2.0.x] Enable hardware serial ports on LPC1768 (#8004)

* Enable hardware serial ports on LPC1768

* Fix compilation errors with other HALs

* FIx order of includes in LPC1768 HAL main.cpp

* Add support for RX_BUFFER_SIZE and TX_BUFFER_SIZE options in Configuration_adv.h
This commit is contained in:
Thomas Moore 2017-10-24 17:28:33 -05:00 committed by Roxy-3D
parent 46aae4c6e7
commit 51fafccc16
21 changed files with 498 additions and 667 deletions

View File

@ -78,30 +78,9 @@
#define BYTE 0 #define BYTE 0
#ifndef USBCON #ifndef USBCON
// Define constants and variables for buffering incoming serial data. We're // We're using a ring buffer (I think), in which rx_buffer_head is the index of the
// using a ring buffer (I think), in which rx_buffer_head is the index of the // location to which to write the next incoming character and rx_buffer_tail is the
// location to which to write the next incoming character and rx_buffer_tail // index of the location from which to read.
// is the index of the location from which to read.
// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
#endif
#ifndef TX_BUFFER_SIZE
#define TX_BUFFER_SIZE 32
#endif
#if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
#error "XON/XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
#endif
#if !IS_POWER_OF_2(RX_BUFFER_SIZE) || RX_BUFFER_SIZE < 2
#error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
#endif
#if TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
#error "TX_BUFFER_SIZE must be 0 or a power of 2 greater than 1."
#endif
#if RX_BUFFER_SIZE > 256 #if RX_BUFFER_SIZE > 256
typedef uint16_t ring_buffer_pos_t; typedef uint16_t ring_buffer_pos_t;
#else #else

View File

@ -20,10 +20,7 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../core/macros.h" #include "../../inc/MarlinConfig.h"
#include "../HAL.h"
#include <stdint.h>
extern "C" { extern "C" {
//#include <lpc17xx_adc.h> //#include <lpc17xx_adc.h>
@ -86,7 +83,7 @@ extern const char errormagic[];
void HAL_adc_enable_channel(int pin) { void HAL_adc_enable_channel(int pin) {
if (!WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) { if (!WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) {
usb_serial.printf("%sINVALID ANALOG PORT:%d\n", errormagic, pin); MYSERIAL.printf("%sINVALID ANALOG PORT:%d\n", errormagic, pin);
kill(MSG_KILLED); kill(MSG_KILLED);
} }
@ -116,7 +113,7 @@ void HAL_adc_enable_channel(int pin) {
uint8_t active_adc = 0; uint8_t active_adc = 0;
void HAL_adc_start_conversion(const 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); MYSERIAL.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
return; return;
} }
LPC_ADC->ADCR &= ~0xFF; // Reset LPC_ADC->ADCR &= ~0xFF; // Reset

View File

@ -41,9 +41,7 @@ void _printf (const char *format, ...);
void _putc(uint8_t c); void _putc(uint8_t c);
uint8_t _getc(); uint8_t _getc();
extern volatile uint32_t _millis; extern "C" volatile uint32_t _millis;
#define USBCON
//arduino: Print.h //arduino: Print.h
#define DEC 10 #define DEC 10
@ -60,7 +58,7 @@ extern volatile uint32_t _millis;
#include "watchdog.h" #include "watchdog.h"
#include "serial.h" #include "serial.h"
#include "HAL_timers.h" #include "HAL_timers.h"
#include "HardwareSerial.h"
#define ST7920_DELAY_1 DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP #define ST7920_DELAY_1 DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP
#define ST7920_DELAY_2 DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP #define ST7920_DELAY_2 DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP
@ -68,7 +66,18 @@ extern volatile uint32_t _millis;
//Serial override //Serial override
extern HalSerial usb_serial; extern HalSerial usb_serial;
#define MYSERIAL usb_serial
#if SERIAL_PORT == -1
#define MYSERIAL usb_serial
#elif SERIAL_PORT == 0
#define MYSERIAL Serial
#elif SERIAL_PORT == 1
#define MYSERIAL Serial1
#elif SERIAL_PORT == 2
#define MYSERIAL Serial2
#elif SERIAL_PORT == 3
#define MYSERIAL Serial3
#endif
#define CRITICAL_SECTION_START uint32_t primask = __get_PRIMASK(); __disable_irq(); #define CRITICAL_SECTION_START uint32_t primask = __get_PRIMASK(); __disable_irq();
#define CRITICAL_SECTION_END if (!primask) __enable_irq(); #define CRITICAL_SECTION_END if (!primask) __enable_irq();

View File

@ -28,7 +28,7 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../HAL.h" #include "../../inc/MarlinConfig.h"
#include "HAL_timers.h" #include "HAL_timers.h"
void HAL_timer_init(void) { void HAL_timer_init(void) {

View File

@ -22,313 +22,280 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../core/macros.h" #include "../../inc/MarlinConfig.h"
#include "../HAL.h"
#include "HardwareSerial.h" #include "HardwareSerial.h"
#define UART3 3
HardwareSerial Serial3 = HardwareSerial(UART3);
volatile uint32_t UART0Status, UART1Status, UART2Status, UART3Status; HardwareSerial Serial = HardwareSerial(LPC_UART0);
volatile uint8_t UART0TxEmpty = 1, UART1TxEmpty = 1, UART2TxEmpty=1, UART3TxEmpty=1; HardwareSerial Serial1 = HardwareSerial((LPC_UART_TypeDef *) LPC_UART1);
volatile uint8_t UART0Buffer[UARTRXQUEUESIZE], UART1Buffer[UARTRXQUEUESIZE], UART2Buffer[UARTRXQUEUESIZE], UART3Buffer[UARTRXQUEUESIZE]; HardwareSerial Serial2 = HardwareSerial(LPC_UART2);
volatile uint32_t UART0RxQueueWritePos = 0, UART1RxQueueWritePos = 0, UART2RxQueueWritePos = 0, UART3RxQueueWritePos = 0; HardwareSerial Serial3 = HardwareSerial(LPC_UART3);
volatile uint32_t UART0RxQueueReadPos = 0, UART1RxQueueReadPos = 0, UART2RxQueueReadPos = 0, UART3RxQueueReadPos = 0;
volatile uint8_t dummy;
void HardwareSerial::begin(uint32_t baudrate) { void HardwareSerial::begin(uint32_t baudrate) {
uint32_t Fdiv;
uint32_t pclkdiv, pclk;
if ( PortNum == 0 ) UART_CFG_Type UARTConfigStruct;
{ PINSEL_CFG_Type PinCfg;
LPC_PINCON->PINSEL0 &= ~0x000000F0; UART_FIFO_CFG_Type FIFOConfig;
LPC_PINCON->PINSEL0 |= 0x00000050; /* RxD0 is P0.3 and TxD0 is P0.2 */
/* 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 UART0 */
pclkdiv = (LPC_SC->PCLKSEL0 >> 6) & 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_UART0->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */ if (UARTx == LPC_UART0) {
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */ /*
LPC_UART0->DLM = Fdiv / 256; * Initialize UART0 pin connect
LPC_UART0->DLL = Fdiv % 256; */
LPC_UART0->LCR = 0x03; /* DLAB = 0 */ PinCfg.Funcnum = 1;
LPC_UART0->FCR = 0x07; /* Enable and reset TX and RX FIFO. */ PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
NVIC_EnableIRQ(UART0_IRQn); PinCfg.Pinnum = 2;
PinCfg.Portnum = 0;
LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART0 interrupt */ PINSEL_ConfigPin(&PinCfg);
} PinCfg.Pinnum = 3;
else if ( PortNum == 1 ) PINSEL_ConfigPin(&PinCfg);
{ }
LPC_PINCON->PINSEL4 &= ~0x0000000F; else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
LPC_PINCON->PINSEL4 |= 0x0000000A; /* Enable RxD1 P2.1, TxD1 P2.0 */ /*
* Initialize UART1 pin connect
/* By default, the PCLKSELx value is zero, thus, the PCLK for */
all the peripherals is 1/4 of the SystemFrequency. */ PinCfg.Funcnum = 1;
/* Bit 8,9 are for UART1 */ PinCfg.OpenDrain = 0;
pclkdiv = (LPC_SC->PCLKSEL0 >> 8) & 0x03; PinCfg.Pinmode = 0;
switch ( pclkdiv ) PinCfg.Pinnum = 15;
{ PinCfg.Portnum = 0;
case 0x00: PINSEL_ConfigPin(&PinCfg);
default: PinCfg.Pinnum = 16;
pclk = SystemCoreClock/4; PINSEL_ConfigPin(&PinCfg);
break; }
case 0x01: else if (UARTx == LPC_UART2) {
pclk = SystemCoreClock; /*
break; * Initialize UART2 pin connect
case 0x02: */
pclk = SystemCoreClock/2; PinCfg.Funcnum = 1;
break; PinCfg.OpenDrain = 0;
case 0x03: PinCfg.Pinmode = 0;
pclk = SystemCoreClock/8; PinCfg.Pinnum = 10;
break; PinCfg.Portnum = 0;
} PINSEL_ConfigPin(&PinCfg);
PinCfg.Pinnum = 11;
LPC_UART1->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */ PINSEL_ConfigPin(&PinCfg);
Fdiv = ( pclk / 16 ) / baudrate ; /*baud rate */ }
LPC_UART1->DLM = Fdiv / 256; else if (UARTx == LPC_UART3) {
LPC_UART1->DLL = Fdiv % 256; /*
LPC_UART1->LCR = 0x03; /* DLAB = 0 */ * Initialize UART2 pin connect
LPC_UART1->FCR = 0x07; /* Enable and reset TX and RX FIFO. */ */
PinCfg.Funcnum = 1;
NVIC_EnableIRQ(UART1_IRQn); PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART1 interrupt */ PinCfg.Pinnum = 0;
} PinCfg.Portnum = 0;
else if ( PortNum == 2 ) PINSEL_ConfigPin(&PinCfg);
{ PinCfg.Pinnum = 1;
//LPC_PINCON->PINSEL4 &= ~0x000F0000; /*Pinsel4 Bits 16-19*/ PINSEL_ConfigPin(&PinCfg);
//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() { /* Initialize UART Configuration parameter structure to default state:
uint8_t rx; * Baudrate = 9600bps
if ( PortNum == 0 ) * 8 data bit
{ * 1 Stop bit
if (UART0RxQueueReadPos == UART0RxQueueWritePos) * None parity
return -1; */
UART_ConfigStructInit(&UARTConfigStruct);
// Read from "head" // Re-configure baudrate
rx = UART0Buffer[UART0RxQueueReadPos]; // grab next byte UARTConfigStruct.Baud_rate = baudrate;
UART0RxQueueReadPos = (UART0RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if ( PortNum == 1 )
{
if (UART1RxQueueReadPos == UART1RxQueueWritePos)
return -1;
// Read from "head" // Initialize eripheral with given to corresponding parameter
rx = UART1Buffer[UART1RxQueueReadPos]; // grab next byte UART_Init(UARTx, &UARTConfigStruct);
UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx;
}
if ( PortNum == 2 )
{
if (UART2RxQueueReadPos == UART2RxQueueWritePos)
return -1;
// Read from "head" // Enable and reset the TX and RX FIFOs
rx = UART2Buffer[UART2RxQueueReadPos]; // grab next byte UART_FIFOConfigStructInit(&FIFOConfig);
UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE; UART_FIFOConfig(UARTx, &FIFOConfig);
return rx;
}
if ( PortNum == 3 )
{
if (UART3RxQueueReadPos == UART3RxQueueWritePos)
return -1;
// Read from "head" // Enable UART Transmit
rx = UART3Buffer[UART3RxQueueReadPos]; // grab next byte UART_TxCmd(UARTx, ENABLE);
UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
return rx; // Configure Interrupts
} UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
return 0; UART_IntConfig(UARTx, UART_INTCFG_RLS, ENABLE);
if (UARTx == LPC_UART0)
NVIC_EnableIRQ(UART0_IRQn);
else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1)
NVIC_EnableIRQ(UART1_IRQn);
else if (UARTx == LPC_UART2)
NVIC_EnableIRQ(UART2_IRQn);
else if (UARTx == LPC_UART3)
NVIC_EnableIRQ(UART3_IRQn);
RxQueueWritePos = RxQueueReadPos = 0;
#if TX_BUFFER_SIZE > 0
TxQueueWritePos = TxQueueReadPos = 0;
#endif
}
int HardwareSerial::peek() {
int byte = -1;
/* Temporarily lock out UART receive interrupts during this read so the UART receive
interrupt won't cause problems with the index values */
UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
if (RxQueueReadPos != RxQueueWritePos)
byte = RxBuffer[RxQueueReadPos];
/* Re-enable UART interrupts */
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
return byte;
}
int HardwareSerial::read() {
int byte = -1;
/* Temporarily lock out UART receive interrupts during this read so the UART receive
interrupt won't cause problems with the index values */
UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
if (RxQueueReadPos != RxQueueWritePos) {
byte = RxBuffer[RxQueueReadPos];
RxQueueReadPos = (RxQueueReadPos + 1) % RX_BUFFER_SIZE;
} }
size_t HardwareSerial::write(uint8_t send) { /* Re-enable UART interrupts */
if ( PortNum == 0 ) UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
{
/* 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 */ return byte;
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() { size_t HardwareSerial::write(uint8_t send) {
if ( PortNum == 0 ) #if TX_BUFFER_SIZE > 0
{ size_t bytes = 0;
UART0RxQueueWritePos = 0; uint32_t fifolvl = 0;
UART0RxQueueReadPos = 0;
} /* If the Tx Buffer is full, wait for space to clear */
if ( PortNum == 1 ) if ((TxQueueWritePos+1) % TX_BUFFER_SIZE == TxQueueReadPos) flushTX();
{
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, ...) { /* Temporarily lock out UART transmit interrupts during this read so the UART transmit interrupt won't
static char buffer[256]; cause problems with the index values */
va_list vArgs; UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
va_start(vArgs, format);
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs); /* LPC17xx.h incorrectly defines FIFOLVL as a uint8_t, when it's actually a 32-bit register */
va_end(vArgs); if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1)
if (length > 0 && length < 256) { fifolvl = *(reinterpret_cast<volatile uint32_t *>(&((LPC_UART1_TypeDef *) UARTx)->FIFOLVL));
for (int i = 0; i < length;) { else
write(buffer[i]); fifolvl = *(reinterpret_cast<volatile uint32_t *>(&UARTx->FIFOLVL));
++i;
} /* If the queue is empty and there's space in the FIFO, immediately send the byte */
} if (TxQueueWritePos == TxQueueReadPos && fifolvl < UART_TX_FIFO_SIZE) {
bytes = UART_Send(UARTx, &send, 1, BLOCKING);
} }
/* Otherwiise, write the byte to the transmit buffer */
else if ((TxQueueWritePos+1) % TX_BUFFER_SIZE != TxQueueReadPos) {
TxBuffer[TxQueueWritePos] = send;
TxQueueWritePos = (TxQueueWritePos+1) % TX_BUFFER_SIZE;
bytes++;
}
/* Re-enable the TX Interrupt */
UART_IntConfig(UARTx, UART_INTCFG_THRE, ENABLE);
return bytes;
#else
return UART_Send(UARTx, &send, 1, BLOCKING);
#endif
}
#if TX_BUFFER_SIZE > 0
void HardwareSerial::flushTX() {
/* Wait for the tx buffer and FIFO to drain */
while (TxQueueWritePos != TxQueueReadPos && UART_CheckBusy(UARTx) == SET);
}
#endif
int HardwareSerial::available() {
return (RxQueueWritePos + RX_BUFFER_SIZE - RxQueueReadPos) % RX_BUFFER_SIZE;
}
void HardwareSerial::flush() {
RxQueueWritePos = 0;
RxQueueReadPos = 0;
}
void HardwareSerial::printf(const char *format, ...) {
char RxBuffer[256];
va_list vArgs;
va_start(vArgs, format);
int length = vsnprintf(RxBuffer, 256, format, vArgs);
va_end(vArgs);
if (length > 0 && length < 256) {
for (int i = 0; i < length; ++i)
write(RxBuffer[i]);
}
}
void HardwareSerial::IRQHandler() {
uint32_t IIRValue;
uint8_t LSRValue, byte;
IIRValue = UART_GetIntId(UARTx);
IIRValue &= UART_IIR_INTID_MASK; /* check bit 1~3, interrupt identification */
if ( IIRValue == UART_IIR_INTID_RLS ) /* Receive Line Status */
{
LSRValue = UART_GetLineStatus(UARTx);
/* Receive Line Status */
if ( LSRValue & (UART_LSR_OE|UART_LSR_PE|UART_LSR_FE|UART_LSR_RXFE|UART_LSR_BI) )
{
/* There are errors or break interrupt */
/* Read LSR will clear the interrupt */
Status = LSRValue;
byte = UART_ReceiveByte(UARTx); /* Dummy read on RX to clear
interrupt, then bail out */
return;
}
}
if ( IIRValue == UART_IIR_INTID_RDA ) /* Receive Data Available */
{
/* Clear the FIFO */
while ( UART_Receive(UARTx, &byte, 1, NONE_BLOCKING) ) {
if ((RxQueueWritePos+1) % RX_BUFFER_SIZE != RxQueueReadPos)
{
RxBuffer[RxQueueWritePos] = byte;
RxQueueWritePos = (RxQueueWritePos+1) % RX_BUFFER_SIZE;
}
else
break;
}
}
else if ( IIRValue == UART_IIR_INTID_CTI ) /* Character timeout indicator */
{
/* Character Time-out indicator */
Status |= 0x100; /* Bit 9 as the CTI error */
}
#if TX_BUFFER_SIZE > 0
if (IIRValue == UART_IIR_INTID_THRE) {
/* Disable THRE interrupt */
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
/* Wait for FIFO buffer empty */
while (UART_CheckBusy(UARTx) == SET);
/* Transfer up to UART_TX_FIFO_SIZE bytes of data */
for (int i = 0; i < UART_TX_FIFO_SIZE && TxQueueWritePos != TxQueueReadPos; i++) {
/* Move a piece of data into the transmit FIFO */
if (UART_Send(UARTx, &TxBuffer[TxQueueReadPos], 1, NONE_BLOCKING))
TxQueueReadPos = (TxQueueReadPos+1) % TX_BUFFER_SIZE;
else
break;
}
/* If there is no more data to send, disable the transmit interrupt - else enable it or keep it enabled */
if (TxQueueWritePos == TxQueueReadPos)
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
else
UART_IntConfig(UARTx, UART_INTCFG_THRE, ENABLE);
}
#endif
}
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
@ -345,68 +312,7 @@ extern "C" {
*****************************************************************************/ *****************************************************************************/
void UART0_IRQHandler (void) void UART0_IRQHandler (void)
{ {
uint8_t IIRValue, LSRValue; Serial.IRQHandler();
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;
}
}
} }
/***************************************************************************** /*****************************************************************************
@ -420,69 +326,9 @@ void UART0_IRQHandler (void)
*****************************************************************************/ *****************************************************************************/
void UART1_IRQHandler (void) void UART1_IRQHandler (void)
{ {
uint8_t IIRValue, LSRValue; Serial1.IRQHandler();
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 ** Function name: UART2_IRQHandler
** **
@ -494,71 +340,13 @@ void UART1_IRQHandler (void)
*****************************************************************************/ *****************************************************************************/
void UART2_IRQHandler (void) void UART2_IRQHandler (void)
{ {
uint8_t IIRValue, LSRValue; Serial2.IRQHandler();
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 ** Function name: UART3_IRQHandler
** **
** Descriptions: UART0 interrupt handler ** Descriptions: UART3 interrupt handler
** **
** parameters: None ** parameters: None
** Returned value: None ** Returned value: None
@ -566,66 +354,7 @@ void UART2_IRQHandler (void)
*****************************************************************************/ *****************************************************************************/
void UART3_IRQHandler (void) void UART3_IRQHandler (void)
{ {
uint8_t IIRValue, LSRValue; Serial3.IRQHandler();
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

View File

@ -28,54 +28,51 @@
#include <Stream.h> #include <Stream.h>
extern "C" { extern "C" {
#include <debug_frmwrk.h> #include <lpc17xx_uart.h>
//#include <lpc17xx_uart.h> #include "lpc17xx_pinsel.h"
} }
#define IER_RBR 0x01
#define IER_THRE 0x02
#define IER_RLS 0x04
#define IIR_PEND 0x01
#define IIR_RLS 0x03
#define IIR_RDA 0x02
#define IIR_CTI 0x06
#define IIR_THRE 0x01
#define LSR_RDR 0x01
#define LSR_OE 0x02
#define LSR_PE 0x04
#define LSR_FE 0x08
#define LSR_BI 0x10
#define LSR_THRE 0x20
#define LSR_TEMT 0x40
#define LSR_RXFE 0x80
#define UARTRXQUEUESIZE 0x10
class HardwareSerial : public Stream { class HardwareSerial : public Stream {
private: private:
uint8_t PortNum; LPC_UART_TypeDef *UARTx;
uint32_t baudrate;
uint32_t Status;
uint8_t RxBuffer[RX_BUFFER_SIZE];
uint32_t RxQueueWritePos;
uint32_t RxQueueReadPos;
#if TX_BUFFER_SIZE > 0
uint8_t TxBuffer[TX_BUFFER_SIZE];
uint32_t TxQueueWritePos;
uint32_t TxQueueReadPos;
#endif
public: public:
HardwareSerial(uint32_t uart) : HardwareSerial(LPC_UART_TypeDef *UARTx)
PortNum(uart) : UARTx(UARTx)
{ , RxQueueWritePos(0)
} , RxQueueReadPos(0)
#if TX_BUFFER_SIZE > 0
, TxQueueWritePos(0)
, TxQueueReadPos(0)
#endif
{
}
void begin(uint32_t baudrate); void begin(uint32_t baudrate);
int peek();
int read(); int read();
size_t write(uint8_t send); size_t write(uint8_t send);
#if TX_BUFFER_SIZE > 0
void flushTX();
#endif
int available(); int available();
void flush(); void flush();
void printf(const char *format, ...); void printf(const char *format, ...);
int peek() {
return 0;
};
operator bool() { return true; } operator bool() { return true; }
void IRQHandler();
void print(const char value[]) { printf("%s" , value); } void print(const char value[]) { printf("%s" , value); }
void print(char value, int = 0) { printf("%c" , value); } void print(char value, int = 0) { printf("%c" , value); }
void print(unsigned char value, int = 0) { printf("%u" , value); } void print(unsigned char value, int = 0) { printf("%u" , value); }
@ -100,9 +97,9 @@ public:
}; };
//extern HardwareSerial Serial0; extern HardwareSerial Serial;
//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

@ -35,8 +35,7 @@ http://arduiniana.org.
// Includes // Includes
// //
//#include <WInterrupts.h> //#include <WInterrupts.h>
#include "../../core/macros.h" #include "../../inc/MarlinConfig.h"
#include "../HAL.h"
#include <stdint.h> #include <stdint.h>
#include <stdarg.h> #include <stdarg.h>
#include "arduino.h" #include "arduino.h"

View File

@ -18,8 +18,7 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../core/macros.h" #include "../../inc/MarlinConfig.h"
#include "../HAL.h"
#include "arduino.h" #include "arduino.h"
#include "pinmapping.h" #include "pinmapping.h"
//#include "HAL_timers.h" //#include "HAL_timers.h"

View File

@ -22,10 +22,9 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
#include <lpc17xx_pinsel.h> #include <lpc17xx_pinsel.h>
#include "HAL.h"
#include "../../core/macros.h"
#include "../../core/types.h"
// Interrupts // Interrupts
void cli(void) { __disable_irq(); } // Disable void cli(void) { __disable_irq(); } // Disable
@ -147,7 +146,7 @@ void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 2
if (LPC1768_PWM_attach_pin(pin, 1, (LPC_PWM1->MR0 - MR0_MARGIN), 0xff)) // locks up if get too close to MR0 value if (LPC1768_PWM_attach_pin(pin, 1, (LPC_PWM1->MR0 - MR0_MARGIN), 0xff)) // locks up if get too close to MR0 value
LPC1768_PWM_write(pin, map(value, 1, 254, 1, (LPC_PWM1->MR0 - MR0_MARGIN))); // map 1-254 onto PWM range LPC1768_PWM_write(pin, map(value, 1, 254, 1, (LPC_PWM1->MR0 - MR0_MARGIN))); // map 1-254 onto PWM range
else { // out of PWM channels else { // out of PWM channels
if (!out_of_PWM_slots) usb_serial.printf(".\nWARNING - OUT OF PWM CHANNELS\n.\n"); //only warn once if (!out_of_PWM_slots) MYSERIAL.printf(".\nWARNING - OUT OF PWM CHANNELS\n.\n"); //only warn once
out_of_PWM_slots = true; out_of_PWM_slots = true;
digitalWrite(pin, value); // treat as a digital pin if out of channels digitalWrite(pin, value); // treat as a digital pin if out of channels
} }

View File

@ -12,6 +12,7 @@ if __name__ == "__main__":
"-ffreestanding", "-ffreestanding",
"-fsigned-char", "-fsigned-char",
"-fno-move-loop-invariants", "-fno-move-loop-invariants",
"-fno-strict-aliasing",
"--specs=nano.specs", "--specs=nano.specs",
"--specs=nosys.specs", "--specs=nosys.specs",

View File

@ -24,6 +24,8 @@ extern "C" {
#include <chanfs/ff.h> #include <chanfs/ff.h>
} }
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "fastio.h" #include "fastio.h"
#include "HAL_timers.h" #include "HAL_timers.h"
#include <stdio.h> #include <stdio.h>
@ -69,21 +71,32 @@ extern "C" void SystemPostInit() {
} }
extern uint32_t MSC_SD_Init(uint8_t pdrv); extern uint32_t MSC_SD_Init(uint8_t pdrv);
extern HalSerial usb_serial;
int main(void) { int main(void) {
(void)MSC_SD_Init(0); (void)MSC_SD_Init(0);
USB_Init(); // USB Initialization USB_Init(); // USB Initialization
USB_Connect(TRUE); // USB Connect USB_Connect(TRUE); // USB Connect
volatile uint32_t usb_timeout = millis() + 2000; volatile uint32_t usb_timeout = millis() + 2000;
while (!USB_Configuration && millis() < usb_timeout) { while (!USB_Configuration && millis() < usb_timeout) {
delay(50); delay(50);
TOGGLE(13); // Flash fast while USB initialisation completes
#if PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Flash fast while USB initialisation completes
#endif
} }
debug_frmwrk_init(); // Only initialize the debug framework if using the USB emulated serial port
usb_serial.printf("\n\nRe-ARM (LPC1768 @ %dMhz) UART0 Initialised\n", SystemCoreClock / 1000000); if ((HalSerial*) &MYSERIAL == &usb_serial)
debug_frmwrk_init();
MYSERIAL.begin(BAUDRATE);
MYSERIAL.printf("\n\nLPC1768 (%dMhz) UART0 Initialised\n", SystemCoreClock / 1000000);
#if TX_BUFFER_SIZE > 0
MYSERIAL.flushTX();
#endif
HAL_timer_init(); HAL_timer_init();

View File

@ -27,7 +27,11 @@
// Runtime pinmapping // Runtime pinmapping
// ****************** // ******************
#define NUM_ANALOG_INPUTS 8 #if SERIAL_PORT == 0
#define NUM_ANALOG_INPUTS 6
#else
#define NUM_ANALOG_INPUTS 8
#endif
const adc_pin_data adc_pin_map[] = { const adc_pin_data adc_pin_map[] = {
{0, 23, 0}, //A0 (T0) - D67 - TEMP_0_PIN {0, 23, 0}, //A0 (T0) - D67 - TEMP_0_PIN
@ -36,27 +40,39 @@ const adc_pin_data adc_pin_map[] = {
{0, 26, 3}, //A3 - D63 {0, 26, 3}, //A3 - D63
{1, 30, 4}, //A4 - D37 - BUZZER_PIN {1, 30, 4}, //A4 - D37 - BUZZER_PIN
{1, 31, 5}, //A5 - D49 - SD_DETECT_PIN {1, 31, 5}, //A5 - D49 - SD_DETECT_PIN
{0, 3, 6}, //A6 - D0 - RXD0 #if SERIAL_PORT != 0
{0, 2, 7} //A7 - D1 - TXD0 {0, 3, 6}, //A6 - D0 - RXD0
{0, 2, 7} //A7 - D1 - TXD0
#endif
}; };
#define analogInputToDigitalPin(p) (p == 0 ? 67: \ constexpr FORCE_INLINE int8_t analogInputToDigitalPin(int8_t p) {
p == 1 ? 68: \ return (p == 0 ? 67:
p == 2 ? 69: \ p == 1 ? 68:
p == 3 ? 63: \ p == 2 ? 69:
p == 4 ? 37: \ p == 3 ? 63:
p == 5 ? 49: \ p == 4 ? 37:
p == 6 ? 0: \ p == 5 ? 49:
p == 7 ? 1: -1) #if SERIAL_PORT != 0
p == 6 ? 0:
p == 7 ? 1:
#endif
-1);
}
#define DIGITAL_PIN_TO_ANALOG_PIN(p) (p == 67 ? 0: \ constexpr FORCE_INLINE int8_t DIGITAL_PIN_TO_ANALOG_PIN(int8_t p) {
p == 68 ? 1: \ return (p == 67 ? 0:
p == 69 ? 2: \ p == 68 ? 1:
p == 63 ? 3: \ p == 69 ? 2:
p == 37 ? 4: \ p == 63 ? 3:
p == 49 ? 5: \ p == 37 ? 4:
p == 0 ? 6: \ p == 49 ? 5:
p == 1 ? 7: -1) #if SERIAL_PORT != 0
p == 0 ? 6:
p == 1 ? 7:
#endif
-1);
}
#define NUM_DIGITAL_PINS 84 #define NUM_DIGITAL_PINS 84

View File

@ -29,6 +29,10 @@
#include "../../../feature/pause.h" #include "../../../feature/pause.h"
#include "../../../module/motion.h" #include "../../../module/motion.h"
#if DISABLED(SDSUPPORT)
#include "../../../module/printcounter.h"
#endif
/** /**
* M125: Store current position and move to filament change position. * M125: Store current position and move to filament change position.
* Called on pause (by M25) to prevent material leaking onto the * Called on pause (by M25) to prevent material leaking onto the

View File

@ -135,7 +135,7 @@ public:
// Code is found in the string. If not found, value_ptr is unchanged. // Code is found in the string. If not found, value_ptr is unchanged.
// This allows "if (seen('A')||seen('B'))" to use the last-found value. // This allows "if (seen('A')||seen('B'))" to use the last-found value.
static bool seen(const char c) { static bool seen(const char c) {
const char *p = strchr(command_args, c); char *p = strchr(command_args, c);
const bool b = !!p; const bool b = !!p;
if (b) value_ptr = DECIMAL_SIGNED(p[1]) ? &p[1] : (char*)NULL; if (b) value_ptr = DECIMAL_SIGNED(p[1]) ? &p[1] : (char*)NULL;
return b; return b;

View File

@ -491,4 +491,12 @@
#define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER)) #define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER))
#define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)) #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED))
// For Re-ARM boards, always use the USB Emulated Serial Port unless RE_ARM_FORCE_SERIAL_PORT is defined
#if MB(RAMPS_14_RE_ARM_EFB) || MB(RAMPS_14_RE_ARM_EEB) || MB(RAMPS_14_RE_ARM_EFF) || MB(RAMPS_14_RE_ARM_EEF) || MB(RAMPS_14_RE_ARM_SF)
#ifndef RE_ARM_FORCE_SERIAL_PORT
#undef SERIAL_PORT
#define SERIAL_PORT -1
#endif
#endif
#endif // CONDITIONALS_LCD_H #endif // CONDITIONALS_LCD_H

View File

@ -0,0 +1,42 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* Conditionals_adv.h
* Defines that depend on advanced onfiguration.
*/
#ifndef CONDITIONALS_ADV_H
#define CONDITIONALS_ADV_H
#ifndef USBCON
// Define constants and variables for buffering incoming serial data.
// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
#endif
#ifndef TX_BUFFER_SIZE
#define TX_BUFFER_SIZE 32
#endif
#endif
#endif // CONDITIONALS_ADV_H

View File

@ -30,6 +30,7 @@
#include "../../Configuration.h" #include "../../Configuration.h"
#include "Conditionals_LCD.h" #include "Conditionals_LCD.h"
#include "../../Configuration_adv.h" #include "../../Configuration_adv.h"
#include "Conditionals_adv.h"
#include "../HAL/HAL.h" #include "../HAL/HAL.h"
#include "../pins/pins.h" #include "../pins/pins.h"
#if defined(__AVR__) && !defined(USBCON) #if defined(__AVR__) && !defined(USBCON)

View File

@ -235,6 +235,24 @@
#error "WEBSITE_URL must be specified." #error "WEBSITE_URL must be specified."
#endif #endif
/**
* Serial
*/
#ifndef USBCON
#if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
#error "XON/XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
#endif
#if !IS_POWER_OF_2(RX_BUFFER_SIZE) || RX_BUFFER_SIZE < 2
#error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
#endif
// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
#if TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
#error "TX_BUFFER_SIZE must be 0 or a power of 2 greater than 1."
#endif
#endif
/** /**
* Dual Stepper Drivers * Dual Stepper Drivers
*/ */

View File

@ -44,17 +44,18 @@
#ifdef _DBGFWK #ifdef _DBGFWK
/* Debug framework */ /* Debug framework */
static Bool debug_frmwrk_initialized = FALSE;
void (*_db_msg)(LPC_UART_TypeDef *UARTx, const void *s); void (*_db_msg)(LPC_UART_TypeDef *UARTx, const void *s) = UARTPuts;
void (*_db_msg_)(LPC_UART_TypeDef *UARTx, const void *s); void (*_db_msg_)(LPC_UART_TypeDef *UARTx, const void *s) = UARTPuts_;
void (*_db_char)(LPC_UART_TypeDef *UARTx, uint8_t ch); void (*_db_char)(LPC_UART_TypeDef *UARTx, uint8_t ch) = UARTPutChar;
void (*_db_dec)(LPC_UART_TypeDef *UARTx, uint8_t decn); void (*_db_dec)(LPC_UART_TypeDef *UARTx, uint8_t decn) = UARTPutHex;
void (*_db_dec_16)(LPC_UART_TypeDef *UARTx, uint16_t decn); void (*_db_dec_16)(LPC_UART_TypeDef *UARTx, uint16_t decn) = UARTPutHex16;
void (*_db_dec_32)(LPC_UART_TypeDef *UARTx, uint32_t decn); void (*_db_dec_32)(LPC_UART_TypeDef *UARTx, uint32_t decn) = UARTPutHex32;
void (*_db_hex)(LPC_UART_TypeDef *UARTx, uint8_t hexn); void (*_db_hex)(LPC_UART_TypeDef *UARTx, uint8_t hexn) = UARTPutDec;
void (*_db_hex_16)(LPC_UART_TypeDef *UARTx, uint16_t hexn); void (*_db_hex_16)(LPC_UART_TypeDef *UARTx, uint16_t hexn) = UARTPutDec16;
void (*_db_hex_32)(LPC_UART_TypeDef *UARTx, uint32_t hexn); void (*_db_hex_32)(LPC_UART_TypeDef *UARTx, uint32_t hexn) = UARTPutDec32;
uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx); uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx) = UARTGetChar;
/*********************************************************************//** /*********************************************************************//**
@ -65,7 +66,8 @@ uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx);
**********************************************************************/ **********************************************************************/
void UARTPutChar (LPC_UART_TypeDef *UARTx, uint8_t ch) void UARTPutChar (LPC_UART_TypeDef *UARTx, uint8_t ch)
{ {
UART_Send(UARTx, &ch, 1, BLOCKING); if (debug_frmwrk_initialized)
UART_Send(UARTx, &ch, 1, BLOCKING);
} }
@ -76,8 +78,11 @@ void UARTPutChar (LPC_UART_TypeDef *UARTx, uint8_t ch)
**********************************************************************/ **********************************************************************/
uint8_t UARTGetChar (LPC_UART_TypeDef *UARTx) uint8_t UARTGetChar (LPC_UART_TypeDef *UARTx)
{ {
uint8_t tmp = 0; uint8_t tmp = 0;
UART_Receive(UARTx, &tmp, 1, BLOCKING);
if (debug_frmwrk_initialized)
UART_Receive(UARTx, &tmp, 1, BLOCKING);
return(tmp); return(tmp);
} }
@ -90,7 +95,10 @@ uint8_t UARTGetChar (LPC_UART_TypeDef *UARTx)
**********************************************************************/ **********************************************************************/
void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str) void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str)
{ {
uint8_t *s = (uint8_t *) str; uint8_t *s = (uint8_t *) str;
if (!debug_frmwrk_initialized)
return;
while (*s) while (*s)
{ {
@ -107,6 +115,9 @@ void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str)
**********************************************************************/ **********************************************************************/
void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str) void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str)
{ {
if (!debug_frmwrk_initialized)
return;
UARTPuts (UARTx, str); UARTPuts (UARTx, str);
UARTPuts (UARTx, "\n\r"); UARTPuts (UARTx, "\n\r");
} }
@ -120,6 +131,9 @@ void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str)
**********************************************************************/ **********************************************************************/
void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum) void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum)
{ {
if (!debug_frmwrk_initialized)
return;
uint8_t c1=decnum%10; uint8_t c1=decnum%10;
uint8_t c2=(decnum/10)%10; uint8_t c2=(decnum/10)%10;
uint8_t c3=(decnum/100)%10; uint8_t c3=(decnum/100)%10;
@ -136,6 +150,9 @@ void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum)
**********************************************************************/ **********************************************************************/
void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum) void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum)
{ {
if (!debug_frmwrk_initialized)
return;
uint8_t c1=decnum%10; uint8_t c1=decnum%10;
uint8_t c2=(decnum/10)%10; uint8_t c2=(decnum/10)%10;
uint8_t c3=(decnum/100)%10; uint8_t c3=(decnum/100)%10;
@ -156,6 +173,9 @@ void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum)
**********************************************************************/ **********************************************************************/
void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum) void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum)
{ {
if (!debug_frmwrk_initialized)
return;
uint8_t c1=decnum%10; uint8_t c1=decnum%10;
uint8_t c2=(decnum/10)%10; uint8_t c2=(decnum/10)%10;
uint8_t c3=(decnum/100)%10; uint8_t c3=(decnum/100)%10;
@ -188,6 +208,9 @@ void UARTPutHex (LPC_UART_TypeDef *UARTx, uint8_t hexnum)
{ {
uint8_t nibble, i; uint8_t nibble, i;
if (!debug_frmwrk_initialized)
return;
UARTPuts(UARTx, "0x"); UARTPuts(UARTx, "0x");
i = 1; i = 1;
do { do {
@ -207,6 +230,9 @@ void UARTPutHex16 (LPC_UART_TypeDef *UARTx, uint16_t hexnum)
{ {
uint8_t nibble, i; uint8_t nibble, i;
if (!debug_frmwrk_initialized)
return;
UARTPuts(UARTx, "0x"); UARTPuts(UARTx, "0x");
i = 3; i = 3;
do { do {
@ -223,7 +249,10 @@ void UARTPutHex16 (LPC_UART_TypeDef *UARTx, uint16_t hexnum)
**********************************************************************/ **********************************************************************/
void UARTPutHex32 (LPC_UART_TypeDef *UARTx, uint32_t hexnum) void UARTPutHex32 (LPC_UART_TypeDef *UARTx, uint32_t hexnum)
{ {
uint8_t nibble, i; uint8_t nibble, i;
if (!debug_frmwrk_initialized)
return;
UARTPuts(UARTx, "0x"); UARTPuts(UARTx, "0x");
i = 7; i = 7;
@ -305,16 +334,7 @@ void debug_frmwrk_init(void)
// Enable UART Transmit // Enable UART Transmit
UART_TxCmd((LPC_UART_TypeDef *)DEBUG_UART_PORT, ENABLE); UART_TxCmd((LPC_UART_TypeDef *)DEBUG_UART_PORT, ENABLE);
_db_msg = UARTPuts; debug_frmwrk_initialized = TRUE;
_db_msg_ = UARTPuts_;
_db_char = UARTPutChar;
_db_hex = UARTPutHex;
_db_hex_16 = UARTPutHex16;
_db_hex_32 = UARTPutHex32;
_db_dec = UARTPutDec;
_db_dec_16 = UARTPutDec16;
_db_dec_32 = UARTPutDec32;
_db_get_char = UARTGetChar;
} }
#endif /*_DBGFWK */ #endif /*_DBGFWK */

View File

@ -17,8 +17,8 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
#ifndef Print_h #ifndef CMSIS_Print_h
#define Print_h #define CMSIS_Print_h
#include <inttypes.h> #include <inttypes.h>

View File

@ -17,8 +17,8 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
#ifndef Printable_h #ifndef CMSIS_Printable_h
#define Printable_h #define CMSIS_Printable_h
#include <stdlib.h> #include <stdlib.h>
#include <inttypes.h> #include <inttypes.h>