HAL whitespace and style cleanup

This commit is contained in:
Scott Lahteine 2017-09-27 04:57:33 -05:00
parent c272f2c84e
commit c2b1d51f16
24 changed files with 449 additions and 829 deletions

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

@ -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);
} }

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);

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

@ -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

@ -32,7 +32,7 @@ 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);
} }

View file

@ -94,7 +94,7 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
extern "C" { extern "C" {
void delay(const 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();

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

@ -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

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