Merge pull request #7770 from thinkyhead/bf2_HAL_cleanups_etc
Some HAL formatting cleanup
This commit is contained in:
commit
baf0bd2b24
@ -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; }
|
||||||
|
@ -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);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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);
|
||||||
|
|
||||||
|
@ -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;
|
||||||
|
@ -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
|
||||||
|
@ -36,19 +36,16 @@ volatile uint32_t UART0RxQueueReadPos = 0, UART1RxQueueReadPos = 0, UART2RxQueue
|
|||||||
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:
|
case 0x00:
|
||||||
default:
|
default:
|
||||||
pclk = SystemCoreClock / 4;
|
pclk = SystemCoreClock / 4;
|
||||||
@ -75,8 +72,7 @@ volatile uint8_t dummy;
|
|||||||
|
|
||||||
LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART0 interrupt */
|
LPC_UART0->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART0 interrupt */
|
||||||
}
|
}
|
||||||
else if ( PortNum == 1 )
|
else if (PortNum == 1) {
|
||||||
{
|
|
||||||
LPC_PINCON->PINSEL4 &= ~0x0000000F;
|
LPC_PINCON->PINSEL4 &= ~0x0000000F;
|
||||||
LPC_PINCON->PINSEL4 |= 0x0000000A; /* Enable RxD1 P2.1, TxD1 P2.0 */
|
LPC_PINCON->PINSEL4 |= 0x0000000A; /* Enable RxD1 P2.1, TxD1 P2.0 */
|
||||||
|
|
||||||
@ -84,8 +80,7 @@ volatile uint8_t dummy;
|
|||||||
all the peripherals is 1/4 of the SystemFrequency. */
|
all the peripherals is 1/4 of the SystemFrequency. */
|
||||||
/* Bit 8,9 are for UART1 */
|
/* Bit 8,9 are for UART1 */
|
||||||
pclkdiv = (LPC_SC->PCLKSEL0 >> 8) & 0x03;
|
pclkdiv = (LPC_SC->PCLKSEL0 >> 8) & 0x03;
|
||||||
switch ( pclkdiv )
|
switch (pclkdiv) {
|
||||||
{
|
|
||||||
case 0x00:
|
case 0x00:
|
||||||
default:
|
default:
|
||||||
pclk = SystemCoreClock / 4;
|
pclk = SystemCoreClock / 4;
|
||||||
@ -112,8 +107,7 @@ volatile uint8_t dummy;
|
|||||||
|
|
||||||
LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART1 interrupt */
|
LPC_UART1->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART1 interrupt */
|
||||||
}
|
}
|
||||||
else if ( PortNum == 2 )
|
else if (PortNum == 2) {
|
||||||
{
|
|
||||||
//LPC_PINCON->PINSEL4 &= ~0x000F0000; /*Pinsel4 Bits 16-19*/
|
//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->PINSEL4 |= 0x000A0000; /* RxD2 is P2.9 and TxD2 is P2.8, value 10*/
|
||||||
LPC_PINCON->PINSEL0 &= ~0x00F00000; /*Pinsel0 Bits 20-23*/
|
LPC_PINCON->PINSEL0 &= ~0x00F00000; /*Pinsel0 Bits 20-23*/
|
||||||
@ -124,8 +118,7 @@ volatile uint8_t dummy;
|
|||||||
all the peripherals is 1/4 of the SystemFrequency. */
|
all the peripherals is 1/4 of the SystemFrequency. */
|
||||||
/* Bit 6~7 is for UART3 */
|
/* Bit 6~7 is for UART3 */
|
||||||
pclkdiv = (LPC_SC->PCLKSEL1 >> 16) & 0x03;
|
pclkdiv = (LPC_SC->PCLKSEL1 >> 16) & 0x03;
|
||||||
switch ( pclkdiv )
|
switch (pclkdiv) {
|
||||||
{
|
|
||||||
case 0x00:
|
case 0x00:
|
||||||
default:
|
default:
|
||||||
pclk = SystemCoreClock / 4;
|
pclk = SystemCoreClock / 4;
|
||||||
@ -142,8 +135,8 @@ volatile uint8_t dummy;
|
|||||||
}
|
}
|
||||||
LPC_UART2->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
|
LPC_UART2->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
|
||||||
Fdiv = (pclk / 16) / baudrate; /*baud rate */
|
Fdiv = (pclk / 16) / baudrate; /*baud rate */
|
||||||
LPC_UART2->DLM = Fdiv / 256;
|
LPC_UART2->DLM = Fdiv >> 8;
|
||||||
LPC_UART2->DLL = Fdiv % 256;
|
LPC_UART2->DLL = Fdiv & 0xFF;
|
||||||
LPC_UART2->LCR = 0x03; /* DLAB = 0 */
|
LPC_UART2->LCR = 0x03; /* DLAB = 0 */
|
||||||
LPC_UART2->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
|
LPC_UART2->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
|
||||||
|
|
||||||
@ -151,8 +144,7 @@ volatile uint8_t dummy;
|
|||||||
|
|
||||||
LPC_UART2->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART3 interrupt */
|
LPC_UART2->IER = IER_RBR | IER_THRE | IER_RLS; /* Enable UART3 interrupt */
|
||||||
}
|
}
|
||||||
else if ( PortNum == 3 )
|
else if (PortNum == 3) {
|
||||||
{
|
|
||||||
LPC_PINCON->PINSEL0 &= ~0x0000000F;
|
LPC_PINCON->PINSEL0 &= ~0x0000000F;
|
||||||
LPC_PINCON->PINSEL0 |= 0x0000000A; /* RxD3 is P0.1 and TxD3 is P0.0 */
|
LPC_PINCON->PINSEL0 |= 0x0000000A; /* RxD3 is P0.1 and TxD3 is P0.0 */
|
||||||
LPC_SC->PCONP |= 1 << 4 | 1 << 25; //Enable PCUART1
|
LPC_SC->PCONP |= 1 << 4 | 1 << 25; //Enable PCUART1
|
||||||
@ -160,8 +152,7 @@ volatile uint8_t dummy;
|
|||||||
all the peripherals is 1/4 of the SystemFrequency. */
|
all the peripherals is 1/4 of the SystemFrequency. */
|
||||||
/* Bit 6~7 is for UART3 */
|
/* Bit 6~7 is for UART3 */
|
||||||
pclkdiv = (LPC_SC->PCLKSEL1 >> 18) & 0x03;
|
pclkdiv = (LPC_SC->PCLKSEL1 >> 18) & 0x03;
|
||||||
switch ( pclkdiv )
|
switch (pclkdiv) {
|
||||||
{
|
|
||||||
case 0x00:
|
case 0x00:
|
||||||
default:
|
default:
|
||||||
pclk = SystemCoreClock / 4;
|
pclk = SystemCoreClock / 4;
|
||||||
@ -178,8 +169,8 @@ volatile uint8_t dummy;
|
|||||||
}
|
}
|
||||||
LPC_UART3->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
|
LPC_UART3->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
|
||||||
Fdiv = (pclk / 16) / baudrate ; /*baud rate */
|
Fdiv = (pclk / 16) / baudrate ; /*baud rate */
|
||||||
LPC_UART3->DLM = Fdiv / 256;
|
LPC_UART3->DLM = Fdiv >> 8;
|
||||||
LPC_UART3->DLL = Fdiv % 256;
|
LPC_UART3->DLL = Fdiv & 0xFF;
|
||||||
LPC_UART3->LCR = 0x03; /* DLAB = 0 */
|
LPC_UART3->LCR = 0x03; /* DLAB = 0 */
|
||||||
LPC_UART3->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
|
LPC_UART3->FCR = 0x07; /* Enable and reset TX and RX FIFO. */
|
||||||
|
|
||||||
@ -191,43 +182,28 @@ volatile uint8_t dummy;
|
|||||||
|
|
||||||
int HardwareSerial::read() {
|
int HardwareSerial::read() {
|
||||||
uint8_t rx;
|
uint8_t rx;
|
||||||
if ( PortNum == 0 )
|
if (PortNum == 0) {
|
||||||
{
|
if (UART0RxQueueReadPos == UART0RxQueueWritePos) return -1;
|
||||||
if (UART0RxQueueReadPos == UART0RxQueueWritePos)
|
|
||||||
return -1;
|
|
||||||
|
|
||||||
// Read from "head"
|
// Read from "head"
|
||||||
rx = UART0Buffer[UART0RxQueueReadPos]; // grab next byte
|
rx = UART0Buffer[UART0RxQueueReadPos]; // grab next byte
|
||||||
UART0RxQueueReadPos = (UART0RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
UART0RxQueueReadPos = (UART0RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
||||||
return rx;
|
return rx;
|
||||||
}
|
}
|
||||||
if ( PortNum == 1 )
|
if (PortNum == 1) {
|
||||||
{
|
if (UART1RxQueueReadPos == UART1RxQueueWritePos) return -1;
|
||||||
if (UART1RxQueueReadPos == UART1RxQueueWritePos)
|
rx = UART1Buffer[UART1RxQueueReadPos];
|
||||||
return -1;
|
|
||||||
|
|
||||||
// Read from "head"
|
|
||||||
rx = UART1Buffer[UART1RxQueueReadPos]; // grab next byte
|
|
||||||
UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
UART1RxQueueReadPos = (UART1RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
||||||
return rx;
|
return rx;
|
||||||
}
|
}
|
||||||
if ( PortNum == 2 )
|
if (PortNum == 2) {
|
||||||
{
|
if (UART2RxQueueReadPos == UART2RxQueueWritePos) return -1;
|
||||||
if (UART2RxQueueReadPos == UART2RxQueueWritePos)
|
rx = UART2Buffer[UART2RxQueueReadPos];
|
||||||
return -1;
|
|
||||||
|
|
||||||
// Read from "head"
|
|
||||||
rx = UART2Buffer[UART2RxQueueReadPos]; // grab next byte
|
|
||||||
UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
UART2RxQueueReadPos = (UART2RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
||||||
return rx;
|
return rx;
|
||||||
}
|
}
|
||||||
if ( PortNum == 3 )
|
if (PortNum == 3) {
|
||||||
{
|
if (UART3RxQueueReadPos == UART3RxQueueWritePos) return -1;
|
||||||
if (UART3RxQueueReadPos == UART3RxQueueWritePos)
|
rx = UART3Buffer[UART3RxQueueReadPos];
|
||||||
return -1;
|
|
||||||
|
|
||||||
// Read from "head"
|
|
||||||
rx = UART3Buffer[UART3RxQueueReadPos]; // grab next byte
|
|
||||||
UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
UART3RxQueueReadPos = (UART3RxQueueReadPos + 1) % UARTRXQUEUESIZE;
|
||||||
return rx;
|
return rx;
|
||||||
}
|
}
|
||||||
@ -235,85 +211,51 @@ volatile uint8_t dummy;
|
|||||||
}
|
}
|
||||||
|
|
||||||
size_t HardwareSerial::write(uint8_t send) {
|
size_t HardwareSerial::write(uint8_t send) {
|
||||||
if ( PortNum == 0 )
|
if (PortNum == 0) {
|
||||||
{
|
|
||||||
/* THRE status, contain valid data */
|
/* THRE status, contain valid data */
|
||||||
while (!(UART0TxEmpty & 0x01));
|
while (!(UART0TxEmpty & 0x01));
|
||||||
LPC_UART0->THR = send;
|
LPC_UART0->THR = send;
|
||||||
UART0TxEmpty = 0; /* not empty in the THR until it shifts out */
|
UART0TxEmpty = 0; /* not empty in the THR until it shifts out */
|
||||||
}
|
}
|
||||||
else if (PortNum == 1)
|
else if (PortNum == 1) {
|
||||||
{
|
|
||||||
|
|
||||||
/* THRE status, contain valid data */
|
|
||||||
while (!(UART1TxEmpty & 0x01));
|
while (!(UART1TxEmpty & 0x01));
|
||||||
LPC_UART1->THR = send;
|
LPC_UART1->THR = send;
|
||||||
UART1TxEmpty = 0; /* not empty in the THR until it shifts out */
|
UART1TxEmpty = 0;
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
else if ( PortNum == 2 )
|
else if (PortNum == 2) {
|
||||||
{
|
|
||||||
/* THRE status, contain valid data */
|
|
||||||
while (!(UART2TxEmpty & 0x01));
|
while (!(UART2TxEmpty & 0x01));
|
||||||
LPC_UART2->THR = send;
|
LPC_UART2->THR = send;
|
||||||
UART2TxEmpty = 0; /* not empty in the THR until it shifts out */
|
UART2TxEmpty = 0;
|
||||||
|
|
||||||
}
|
}
|
||||||
else if ( PortNum == 3 )
|
else if (PortNum == 3) {
|
||||||
{
|
|
||||||
/* THRE status, contain valid data */
|
|
||||||
while (!(UART3TxEmpty & 0x01));
|
while (!(UART3TxEmpty & 0x01));
|
||||||
LPC_UART3->THR = send;
|
LPC_UART3->THR = send;
|
||||||
UART3TxEmpty = 0; /* not empty in the THR until it shifts out */
|
UART3TxEmpty = 0;
|
||||||
|
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
int HardwareSerial::available() {
|
int HardwareSerial::available() {
|
||||||
if (PortNum == 0)
|
if (PortNum == 0)
|
||||||
{
|
|
||||||
return (UART0RxQueueWritePos + UARTRXQUEUESIZE - UART0RxQueueReadPos) % UARTRXQUEUESIZE;
|
return (UART0RxQueueWritePos + UARTRXQUEUESIZE - UART0RxQueueReadPos) % UARTRXQUEUESIZE;
|
||||||
}
|
|
||||||
if (PortNum == 1)
|
if (PortNum == 1)
|
||||||
{
|
|
||||||
return (UART1RxQueueWritePos + UARTRXQUEUESIZE - UART1RxQueueReadPos) % UARTRXQUEUESIZE;
|
return (UART1RxQueueWritePos + UARTRXQUEUESIZE - UART1RxQueueReadPos) % UARTRXQUEUESIZE;
|
||||||
}
|
|
||||||
if (PortNum == 2)
|
if (PortNum == 2)
|
||||||
{
|
|
||||||
return (UART2RxQueueWritePos + UARTRXQUEUESIZE - UART2RxQueueReadPos) % UARTRXQUEUESIZE;
|
return (UART2RxQueueWritePos + UARTRXQUEUESIZE - UART2RxQueueReadPos) % UARTRXQUEUESIZE;
|
||||||
}
|
|
||||||
if (PortNum == 3)
|
if (PortNum == 3)
|
||||||
{
|
|
||||||
return (UART3RxQueueWritePos + UARTRXQUEUESIZE - UART3RxQueueReadPos) % UARTRXQUEUESIZE;
|
return (UART3RxQueueWritePos + UARTRXQUEUESIZE - UART3RxQueueReadPos) % UARTRXQUEUESIZE;
|
||||||
}
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void HardwareSerial::flush() {
|
void HardwareSerial::flush() {
|
||||||
if (PortNum == 0)
|
if (PortNum == 0)
|
||||||
{
|
UART0RxQueueWritePos = UART0RxQueueReadPos = 0;
|
||||||
UART0RxQueueWritePos = 0;
|
|
||||||
UART0RxQueueReadPos = 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
if (PortNum == 1)
|
if (PortNum == 1)
|
||||||
{
|
UART1RxQueueWritePos = UART1RxQueueReadPos = 0;
|
||||||
UART1RxQueueWritePos = 0;
|
|
||||||
UART1RxQueueReadPos = 0;
|
|
||||||
}
|
|
||||||
if (PortNum == 2)
|
if (PortNum == 2)
|
||||||
{
|
UART2RxQueueWritePos = UART2RxQueueReadPos = 0;
|
||||||
UART2RxQueueWritePos = 0;
|
|
||||||
UART2RxQueueReadPos = 0;
|
|
||||||
}
|
|
||||||
if (PortNum == 3)
|
if (PortNum == 3)
|
||||||
{
|
UART3RxQueueWritePos = UART3RxQueueReadPos = 0;
|
||||||
UART3RxQueueWritePos = 0;
|
|
||||||
UART3RxQueueReadPos = 0;
|
|
||||||
}
|
|
||||||
return;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void HardwareSerial::printf(const char *format, ...) {
|
void HardwareSerial::printf(const char *format, ...) {
|
||||||
@ -322,316 +264,69 @@ return;
|
|||||||
va_start(vArgs, format);
|
va_start(vArgs, format);
|
||||||
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
|
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
|
||||||
va_end(vArgs);
|
va_end(vArgs);
|
||||||
if (length > 0 && length < 256) {
|
if (length > 0 && length < 256)
|
||||||
for (int i = 0; i < length;) {
|
for (int i = 0; i < length; ++i)
|
||||||
write(buffer[i]);
|
write(buffer[i]);
|
||||||
++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
|
||||||
}
|
}
|
||||||
|
@ -29,7 +29,6 @@
|
|||||||
|
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#include <debug_frmwrk.h>
|
#include <debug_frmwrk.h>
|
||||||
|
|
||||||
//#include <lpc17xx_uart.h>
|
//#include <lpc17xx_uart.h>
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -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_
|
||||||
|
@ -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);
|
||||||
|
@ -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
|
||||||
|
@ -25,13 +25,14 @@
|
|||||||
#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);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -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();
|
||||||
|
@ -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);
|
||||||
|
@ -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
|
|
||||||
|
@ -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
|
||||||
|
@ -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);
|
||||||
|
|
||||||
|
@ -21,21 +21,14 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
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)
|
||||||
#endif
|
#endif
|
||||||
@ -44,75 +37,48 @@
|
|||||||
#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)
|
||||||
|
|
||||||
/// set pin as input
|
|
||||||
#define _SET_INPUT(p) do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1); \
|
#define _SET_INPUT(p) do { CORE_PIN ## p ## _CONFIG = PORT_PCR_MUX(1); \
|
||||||
GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 0; \
|
GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 0; \
|
||||||
} while (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; \
|
#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; \
|
GPIO_BITBAND(CORE_PIN ## p ## _DDRREG , CORE_PIN ## p ## _BIT) = 1; \
|
||||||
} while (0)
|
} 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
|
||||||
|
@ -22,7 +22,7 @@
|
|||||||
|
|
||||||
#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)
|
||||||
|
|
||||||
@ -36,4 +36,4 @@
|
|||||||
|
|
||||||
#endif // USE_WATCHDOG
|
#endif // USE_WATCHDOG
|
||||||
|
|
||||||
#endif
|
#endif // __MK64FX512__ || __MK66FX1M0__
|
||||||
|
@ -109,7 +109,7 @@ 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
|
||||||
|
Loading…
Reference in New Issue
Block a user