Add new LPC include folder
This commit is contained in:
335
Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.cpp
Normal file
335
Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.cpp
Normal file
@ -0,0 +1,335 @@
|
||||
/**
|
||||
* 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "HardwareSerial.h"
|
||||
|
||||
#if SERIAL_PORT == 0 || SERIAL_PORT_2 == 0
|
||||
HardwareSerial Serial = HardwareSerial(LPC_UART0);
|
||||
#elif SERIAL_PORT == 1 || SERIAL_PORT_2 == 1
|
||||
HardwareSerial Serial1 = HardwareSerial((LPC_UART_TypeDef *) LPC_UART1);
|
||||
#elif SERIAL_PORT == 2 || SERIAL_PORT_2 == 2
|
||||
HardwareSerial Serial2 = HardwareSerial(LPC_UART2);
|
||||
#elif SERIAL_PORT == 3 || SERIAL_PORT_2 == 3
|
||||
HardwareSerial Serial3 = HardwareSerial(LPC_UART3);
|
||||
#endif
|
||||
|
||||
void HardwareSerial::begin(uint32_t baudrate) {
|
||||
|
||||
UART_CFG_Type UARTConfigStruct;
|
||||
PINSEL_CFG_Type PinCfg;
|
||||
UART_FIFO_CFG_Type FIFOConfig;
|
||||
|
||||
if (Baudrate == baudrate) return; // No need to re-initialize
|
||||
|
||||
if (UARTx == LPC_UART0) {
|
||||
// Initialize UART0 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 2;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 3;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
} else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
|
||||
// Initialize UART1 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 15;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 16;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
} else if (UARTx == LPC_UART2) {
|
||||
// Initialize UART2 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 10;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 11;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
} else if (UARTx == LPC_UART3) {
|
||||
// Initialize UART2 pin connect
|
||||
PinCfg.Funcnum = 1;
|
||||
PinCfg.OpenDrain = 0;
|
||||
PinCfg.Pinmode = 0;
|
||||
PinCfg.Pinnum = 0;
|
||||
PinCfg.Portnum = 0;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
PinCfg.Pinnum = 1;
|
||||
PINSEL_ConfigPin(&PinCfg);
|
||||
}
|
||||
|
||||
/* Initialize UART Configuration parameter structure to default state:
|
||||
* Baudrate = 9600bps
|
||||
* 8 data bit
|
||||
* 1 Stop bit
|
||||
* None parity
|
||||
*/
|
||||
UART_ConfigStructInit(&UARTConfigStruct);
|
||||
|
||||
// Re-configure baudrate
|
||||
UARTConfigStruct.Baud_rate = baudrate;
|
||||
|
||||
// Initialize eripheral with given to corresponding parameter
|
||||
UART_Init(UARTx, &UARTConfigStruct);
|
||||
|
||||
// Enable and reset the TX and RX FIFOs
|
||||
UART_FIFOConfigStructInit(&FIFOConfig);
|
||||
UART_FIFOConfig(UARTx, &FIFOConfig);
|
||||
|
||||
// Enable UART Transmit
|
||||
UART_TxCmd(UARTx, ENABLE);
|
||||
|
||||
// Configure Interrupts
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RLS, ENABLE);
|
||||
|
||||
// Set proper priority and enable interrupts
|
||||
if (UARTx == LPC_UART0) {
|
||||
NVIC_SetPriority(UART0_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART0_IRQn);
|
||||
}
|
||||
else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
|
||||
NVIC_SetPriority(UART1_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART1_IRQn);
|
||||
}
|
||||
else if (UARTx == LPC_UART2) {
|
||||
NVIC_SetPriority(UART2_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART2_IRQn);
|
||||
}
|
||||
else if (UARTx == LPC_UART3) {
|
||||
NVIC_SetPriority(UART3_IRQn, NVIC_EncodePriority(0, 3, 0));
|
||||
NVIC_EnableIRQ(UART3_IRQn);
|
||||
}
|
||||
|
||||
RxQueueWritePos = RxQueueReadPos = 0;
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
TxQueueWritePos = TxQueueReadPos = 0;
|
||||
#endif
|
||||
|
||||
// Save the configured baudrate
|
||||
Baudrate = baudrate;
|
||||
}
|
||||
|
||||
int16_t HardwareSerial::peek() {
|
||||
int16_t 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;
|
||||
}
|
||||
|
||||
int16_t HardwareSerial::read() {
|
||||
int16_t 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;
|
||||
}
|
||||
|
||||
// Re-enable UART interrupts
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
|
||||
return byte;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::write(uint8_t send) {
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
size_t bytes = 0;
|
||||
uint32_t fifolvl = 0;
|
||||
|
||||
// If the Tx Buffer is full, wait for space to clear
|
||||
if ((TxQueueWritePos+1) % TX_BUFFER_SIZE == TxQueueReadPos) flushTX();
|
||||
|
||||
// Temporarily lock out UART transmit interrupts during this read so the UART transmit interrupt won't
|
||||
// cause problems with the index values
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
|
||||
|
||||
// LPC17xx.h incorrectly defines FIFOLVL as a uint8_t, when it's actually a 32-bit register
|
||||
if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1) {
|
||||
fifolvl = *(reinterpret_cast<volatile uint32_t *>(&((LPC_UART1_TypeDef *) UARTx)->FIFOLVL));
|
||||
} else fifolvl = *(reinterpret_cast<volatile uint32_t *>(&UARTx->FIFOLVL));
|
||||
|
||||
// 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
|
||||
|
||||
size_t HardwareSerial::available() {
|
||||
return (RxQueueWritePos + RX_BUFFER_SIZE - RxQueueReadPos) % RX_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
void HardwareSerial::flush() {
|
||||
RxQueueWritePos = 0;
|
||||
RxQueueReadPos = 0;
|
||||
}
|
||||
|
||||
size_t 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 (size_t i = 0; i < (size_t)length; ++i)
|
||||
write(RxBuffer[i]);
|
||||
}
|
||||
return length;
|
||||
}
|
||||
|
||||
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
|
||||
|
||||
// Receive Line Status
|
||||
if (IIRValue == UART_IIR_INTID_RLS) {
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
// Receive Data Available
|
||||
if (IIRValue == UART_IIR_INTID_RDA) {
|
||||
// Clear the FIFO
|
||||
while (UART_Receive(UARTx, &byte, 1, NONE_BLOCKING)) {
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
emergency_parser.update(emergency_state, byte);
|
||||
#endif
|
||||
if ((RxQueueWritePos + 1) % RX_BUFFER_SIZE != RxQueueReadPos) {
|
||||
RxBuffer[RxQueueWritePos] = byte;
|
||||
RxQueueWritePos = (RxQueueWritePos + 1) % RX_BUFFER_SIZE;
|
||||
} else
|
||||
break;
|
||||
}
|
||||
// Character timeout indicator
|
||||
} else if (IIRValue == UART_IIR_INTID_CTI) {
|
||||
// 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
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
void UART0_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 0 || SERIAL_PORT_2 == 0
|
||||
Serial.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
void UART1_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1
|
||||
Serial1.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
void UART2_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2
|
||||
Serial2.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
void UART3_IRQHandler(void) {
|
||||
#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3
|
||||
Serial3.IRQHandler();
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TARGET_LPC1768
|
91
Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.h
Normal file
91
Marlin/src/HAL/HAL_LPC1768/include/HardwareSerial.h
Normal file
@ -0,0 +1,91 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef HARDWARE_SERIAL_H_
|
||||
#define HARDWARE_SERIAL_H_
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/emergency_parser.h"
|
||||
#endif
|
||||
|
||||
#include <stdarg.h>
|
||||
#include <stdio.h>
|
||||
#include <Stream.h>
|
||||
|
||||
extern "C" {
|
||||
#include <lpc17xx_uart.h>
|
||||
#include "lpc17xx_pinsel.h"
|
||||
}
|
||||
|
||||
class HardwareSerial : public Stream {
|
||||
private:
|
||||
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
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
EmergencyParser::State emergency_state;
|
||||
#endif
|
||||
|
||||
public:
|
||||
HardwareSerial(LPC_UART_TypeDef *UARTx)
|
||||
: UARTx(UARTx)
|
||||
, Baudrate(0)
|
||||
, RxQueueWritePos(0)
|
||||
, RxQueueReadPos(0)
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
, TxQueueWritePos(0)
|
||||
, TxQueueReadPos(0)
|
||||
#endif
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
, emergency_state(EmergencyParser::State::EP_RESET)
|
||||
#endif
|
||||
{
|
||||
}
|
||||
|
||||
void begin(uint32_t baudrate);
|
||||
int16_t peek();
|
||||
int16_t read();
|
||||
size_t write(uint8_t send);
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
void flushTX();
|
||||
#endif
|
||||
size_t available();
|
||||
void flush();
|
||||
size_t printf(const char *format, ...);
|
||||
|
||||
operator bool() { return true; }
|
||||
|
||||
void IRQHandler();
|
||||
|
||||
};
|
||||
|
||||
#endif // MARLIN_SRC_HAL_HAL_SERIAL_H_
|
329
Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.cpp
Normal file
329
Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.cpp
Normal file
@ -0,0 +1,329 @@
|
||||
/*
|
||||
* SoftwareSerial.cpp (formerly NewSoftSerial.cpp)
|
||||
*
|
||||
* Multi-instance software serial library for Arduino/Wiring
|
||||
* -- Interrupt-driven receive and other improvements by ladyada
|
||||
* (http://ladyada.net)
|
||||
* -- Tuning, circular buffer, derivation from class Print/Stream,
|
||||
* multi-instance support, porting to 8MHz processors,
|
||||
* various optimizations, PROGMEM delay tables, inverse logic and
|
||||
* direct port writing by Mikal Hart (http://www.arduiniana.org)
|
||||
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
|
||||
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
|
||||
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* This library 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
|
||||
* Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public
|
||||
* License along with this library; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*
|
||||
* The latest version of this library can always be found at
|
||||
* http://arduiniana.org.
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
//
|
||||
// Includes
|
||||
//
|
||||
//#include <WInterrupts.h>
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../Delay.h"
|
||||
#include <stdint.h>
|
||||
#include <stdarg.h>
|
||||
#include <Arduino.h>
|
||||
#include <pinmapping.h>
|
||||
#include "../fastio.h"
|
||||
#include "SoftwareSerial.h"
|
||||
|
||||
void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
|
||||
void GpioDisableInt(uint32_t port, uint32_t pin);
|
||||
//
|
||||
// Statics
|
||||
//
|
||||
SoftwareSerial *SoftwareSerial::active_object = 0;
|
||||
unsigned char SoftwareSerial::_receive_buffer[_SS_MAX_RX_BUFF];
|
||||
volatile uint8_t SoftwareSerial::_receive_buffer_tail = 0;
|
||||
volatile uint8_t SoftwareSerial::_receive_buffer_head = 0;
|
||||
|
||||
typedef struct _DELAY_TABLE {
|
||||
long baud;
|
||||
uint16_t rx_delay_centering;
|
||||
uint16_t rx_delay_intrabit;
|
||||
uint16_t rx_delay_stopbit;
|
||||
uint16_t tx_delay;
|
||||
} DELAY_TABLE;
|
||||
|
||||
// rough delay estimation
|
||||
static const DELAY_TABLE table[] = {
|
||||
//baud |rxcenter|rxintra |rxstop |tx { 250000, 2, 4, 4, 4, }, //Done but not good due to instruction cycle error { 115200, 4, 8, 8, 8, }, //Done but not good due to instruction cycle error
|
||||
//{ 74880, 69, 139, 62, 162, }, // estimation
|
||||
//{ 57600, 100, 185, 1, 208, }, // Done but not good due to instruction cycle error
|
||||
//{ 38400, 13, 26, 26, 26, }, // Done
|
||||
//{ 19200, 26, 52, 52, 52, }, // Done { 9600, 52, 104, 104, 104, }, // Done
|
||||
//{ 4800, 104, 208, 208, 208, },
|
||||
//{ 2400, 208, 417, 417, 417, },
|
||||
//{ 1200, 416, 833, 833, 833,},
|
||||
};
|
||||
|
||||
//
|
||||
// Private methods
|
||||
//
|
||||
|
||||
inline void SoftwareSerial::tunedDelay(const uint32_t count) {
|
||||
DELAY_US(count);
|
||||
}
|
||||
|
||||
// This function sets the current object as the "listening"
|
||||
// one and returns true if it replaces another
|
||||
bool SoftwareSerial::listen() {
|
||||
if (!_rx_delay_stopbit)
|
||||
return false;
|
||||
|
||||
if (active_object != this) {
|
||||
if (active_object)
|
||||
active_object->stopListening();
|
||||
|
||||
_buffer_overflow = false;
|
||||
_receive_buffer_head = _receive_buffer_tail = 0;
|
||||
active_object = this;
|
||||
|
||||
setRxIntMsk(true);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// Stop listening. Returns true if we were actually listening.
|
||||
bool SoftwareSerial::stopListening() {
|
||||
if (active_object == this) {
|
||||
setRxIntMsk(false);
|
||||
active_object = NULL;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
//
|
||||
// The receive routine called by the interrupt handler
|
||||
//
|
||||
void SoftwareSerial::recv() {
|
||||
uint8_t d = 0;
|
||||
|
||||
// If RX line is high, then we don't see any start bit
|
||||
// so interrupt is probably not for us
|
||||
if (_inverse_logic ? rx_pin_read() : !rx_pin_read()) {
|
||||
// Disable further interrupts during reception, this prevents
|
||||
// triggering another interrupt directly after we return, which can
|
||||
// cause problems at higher baudrates.
|
||||
setRxIntMsk(false);//__disable_irq();//
|
||||
|
||||
// Wait approximately 1/2 of a bit width to "center" the sample
|
||||
tunedDelay(_rx_delay_centering);
|
||||
// Read each of the 8 bits
|
||||
for (uint8_t i=8; i > 0; --i) {
|
||||
tunedDelay(_rx_delay_intrabit);
|
||||
d >>= 1;
|
||||
if (rx_pin_read()) d |= 0x80;
|
||||
}
|
||||
|
||||
if (_inverse_logic) d = ~d;
|
||||
|
||||
// if buffer full, set the overflow flag and return
|
||||
uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
|
||||
if (next != _receive_buffer_head) {
|
||||
// save new data in buffer: tail points to where byte goes
|
||||
_receive_buffer[_receive_buffer_tail] = d; // save new byte
|
||||
_receive_buffer_tail = next;
|
||||
}
|
||||
else {
|
||||
_buffer_overflow = true;
|
||||
}
|
||||
tunedDelay(_rx_delay_stopbit);
|
||||
// Re-enable interrupts when we're sure to be inside the stop bit
|
||||
setRxIntMsk(true); //__enable_irq();//
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t SoftwareSerial::rx_pin_read() {
|
||||
return digitalRead(_receivePin);
|
||||
}
|
||||
|
||||
//
|
||||
// Interrupt handling
|
||||
//
|
||||
|
||||
/* static */
|
||||
inline void SoftwareSerial::handle_interrupt() {
|
||||
if (active_object)
|
||||
active_object->recv();
|
||||
}
|
||||
extern "C" void intWrapper() {
|
||||
SoftwareSerial::handle_interrupt();
|
||||
}
|
||||
//
|
||||
// Constructor
|
||||
//
|
||||
SoftwareSerial::SoftwareSerial(pin_t receivePin, pin_t transmitPin, bool inverse_logic /* = false */) :
|
||||
_rx_delay_centering(0),
|
||||
_rx_delay_intrabit(0),
|
||||
_rx_delay_stopbit(0),
|
||||
_tx_delay(0),
|
||||
_buffer_overflow(false),
|
||||
_inverse_logic(inverse_logic) {
|
||||
setTX(transmitPin);
|
||||
setRX(receivePin);
|
||||
}
|
||||
|
||||
//
|
||||
// Destructor
|
||||
//
|
||||
SoftwareSerial::~SoftwareSerial() {
|
||||
end();
|
||||
}
|
||||
|
||||
void SoftwareSerial::setTX(pin_t tx) {
|
||||
// First write, then set output. If we do this the other way around,
|
||||
// the pin would be output low for a short while before switching to
|
||||
// output hihg. Now, it is input with pullup for a short while, which
|
||||
// is fine. With inverse logic, either order is fine.
|
||||
|
||||
digitalWrite(tx, _inverse_logic ? LOW : HIGH);
|
||||
pinMode(tx,OUTPUT);
|
||||
_transmitPin = tx;
|
||||
}
|
||||
|
||||
void SoftwareSerial::setRX(pin_t rx) {
|
||||
pinMode(rx, INPUT_PULLUP); // pullup for normal logic!
|
||||
//if (!_inverse_logic)
|
||||
// digitalWrite(rx, HIGH);
|
||||
_receivePin = rx;
|
||||
_receivePort = LPC1768_PIN_PORT(rx);
|
||||
_receivePortPin = LPC1768_PIN_PIN(rx);
|
||||
/* GPIO_T * rxPort = digitalPinToPort(rx);
|
||||
_receivePortRegister = portInputRegister(rxPort);
|
||||
_receiveBitMask = digitalPinToBitMask(rx);*/
|
||||
}
|
||||
|
||||
//
|
||||
// Public methods
|
||||
//
|
||||
|
||||
void SoftwareSerial::begin(long speed) {
|
||||
_rx_delay_centering = _rx_delay_intrabit = _rx_delay_stopbit = _tx_delay = 0;
|
||||
|
||||
for(uint8_t i = 0; i < sizeof(table)/sizeof(table[0]); ++i) {
|
||||
long baud = table[i].baud;
|
||||
if (baud == speed) {
|
||||
_rx_delay_centering = table[i].rx_delay_centering;
|
||||
_rx_delay_intrabit = table[i].rx_delay_intrabit;
|
||||
_rx_delay_stopbit = table[i].rx_delay_stopbit;
|
||||
_tx_delay = table[i].tx_delay;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
attachInterrupt(_receivePin, intWrapper, CHANGE); //this->handle_interrupt, CHANGE);
|
||||
|
||||
listen();
|
||||
tunedDelay(_tx_delay);
|
||||
|
||||
}
|
||||
|
||||
void SoftwareSerial::setRxIntMsk(bool enable) {
|
||||
if (enable)
|
||||
GpioEnableInt(_receivePort,_receivePin,CHANGE);
|
||||
else
|
||||
GpioDisableInt(_receivePort,_receivePin);
|
||||
}
|
||||
|
||||
void SoftwareSerial::end() {
|
||||
stopListening();
|
||||
}
|
||||
|
||||
|
||||
// Read data from buffer
|
||||
int16_t SoftwareSerial::read() {
|
||||
if (!isListening()) return -1;
|
||||
|
||||
// Empty buffer?
|
||||
if (_receive_buffer_head == _receive_buffer_tail) return -1;
|
||||
|
||||
// Read from "head"
|
||||
uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte
|
||||
_receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF;
|
||||
return d;
|
||||
}
|
||||
|
||||
size_t SoftwareSerial::available() {
|
||||
if (!isListening()) return 0;
|
||||
|
||||
return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
|
||||
}
|
||||
|
||||
size_t SoftwareSerial::write(uint8_t b) {
|
||||
// By declaring these as local variables, the compiler will put them
|
||||
// in registers _before_ disabling interrupts and entering the
|
||||
// critical timing sections below, which makes it a lot easier to
|
||||
// verify the cycle timings
|
||||
|
||||
bool inv = _inverse_logic;
|
||||
uint16_t delay = _tx_delay;
|
||||
|
||||
if (inv) b = ~b;
|
||||
|
||||
cli(); // turn off interrupts for a clean txmit
|
||||
|
||||
// Write the start bit
|
||||
digitalWrite(_transmitPin, !!inv);
|
||||
|
||||
tunedDelay(delay);
|
||||
|
||||
// Write each of the 8 bits
|
||||
for (uint8_t i = 8; i > 0; --i) {
|
||||
digitalWrite(_transmitPin, b & 1); // send 1 //(GPIO_Desc[_transmitPin].P)->DOUT |= GPIO_Desc[_transmitPin].bit;
|
||||
// send 0 //(GPIO_Desc[_transmitPin].P)->DOUT &= ~GPIO_Desc[_transmitPin].bit;
|
||||
tunedDelay(delay);
|
||||
b >>= 1;
|
||||
}
|
||||
|
||||
// restore pin to natural state
|
||||
digitalWrite(_transmitPin, !inv);
|
||||
|
||||
sei(); // turn interrupts back on
|
||||
tunedDelay(delay);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
void SoftwareSerial::flush() {
|
||||
if (!isListening()) return;
|
||||
|
||||
cli();
|
||||
_receive_buffer_head = _receive_buffer_tail = 0;
|
||||
sei();
|
||||
}
|
||||
|
||||
int16_t SoftwareSerial::peek() {
|
||||
if (!isListening())
|
||||
return -1;
|
||||
|
||||
// Empty buffer?
|
||||
if (_receive_buffer_head == _receive_buffer_tail)
|
||||
return -1;
|
||||
|
||||
// Read from "head"
|
||||
return _receive_buffer[_receive_buffer_head];
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
120
Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.h
Normal file
120
Marlin/src/HAL/HAL_LPC1768/include/SoftwareSerial.h
Normal file
@ -0,0 +1,120 @@
|
||||
/*
|
||||
* SoftwareSerial.h (formerly NewSoftSerial.h)
|
||||
*
|
||||
* Multi-instance software serial library for Arduino/Wiring
|
||||
* -- Interrupt-driven receive and other improvements by ladyada
|
||||
* (http://ladyada.net)
|
||||
* -- Tuning, circular buffer, derivation from class Print/Stream,
|
||||
* multi-instance support, porting to 8MHz processors,
|
||||
* various optimizations, PROGMEM delay tables, inverse logic and
|
||||
* direct port writing by Mikal Hart (http://www.arduiniana.org)
|
||||
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
|
||||
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
|
||||
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* This library 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
|
||||
* Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public
|
||||
* License along with this library; if not, write to the Free Software
|
||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*
|
||||
* The latest version of this library can always be found at
|
||||
* http://arduiniana.org.
|
||||
*/
|
||||
|
||||
#ifndef SOFTWARESERIAL_H
|
||||
#define SOFTWARESERIAL_H
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <stdint.h>
|
||||
//#include "serial.h"
|
||||
#include <Stream.h>
|
||||
#include <Print.h>
|
||||
|
||||
/******************************************************************************
|
||||
* Definitions
|
||||
******************************************************************************/
|
||||
|
||||
#define _SS_MAX_RX_BUFF 64 // RX buffer size
|
||||
|
||||
class SoftwareSerial : public Stream
|
||||
{
|
||||
private:
|
||||
// per object data
|
||||
pin_t _receivePin;
|
||||
pin_t _transmitPin;
|
||||
// uint32_t _receiveBitMask; // for rx interrupts
|
||||
uint32_t _receivePort;
|
||||
uint32_t _receivePortPin;
|
||||
|
||||
|
||||
// Expressed as 4-cycle delays (must never be 0!)
|
||||
uint16_t _rx_delay_centering;
|
||||
uint16_t _rx_delay_intrabit;
|
||||
uint16_t _rx_delay_stopbit;
|
||||
uint16_t _tx_delay;
|
||||
|
||||
uint16_t _buffer_overflow:1;
|
||||
uint16_t _inverse_logic:1;
|
||||
|
||||
// static data
|
||||
static unsigned char _receive_buffer[_SS_MAX_RX_BUFF];
|
||||
static volatile uint8_t _receive_buffer_tail;
|
||||
static volatile uint8_t _receive_buffer_head;
|
||||
static SoftwareSerial *active_object;
|
||||
|
||||
// private methods
|
||||
void recv();
|
||||
uint32_t rx_pin_read();
|
||||
void tx_pin_write(uint8_t pin_state);
|
||||
void setTX(pin_t transmitPin);
|
||||
void setRX(pin_t receivePin);
|
||||
void setRxIntMsk(bool enable);
|
||||
|
||||
// private static method for timing
|
||||
static inline void tunedDelay(uint32_t delay);
|
||||
|
||||
public:
|
||||
// public methods
|
||||
|
||||
SoftwareSerial(pin_t receivePin, pin_t transmitPin, bool inverse_logic = false);
|
||||
~SoftwareSerial();
|
||||
void begin(long speed);
|
||||
bool listen();
|
||||
void end();
|
||||
bool isListening() { return this == active_object; }
|
||||
bool stopListening();
|
||||
bool overflow() { bool ret = _buffer_overflow; if (ret) _buffer_overflow = false; return ret; }
|
||||
int16_t peek();
|
||||
|
||||
virtual size_t write(uint8_t byte);
|
||||
virtual int16_t read();
|
||||
virtual size_t available();
|
||||
virtual void flush();
|
||||
operator bool() { return true; }
|
||||
|
||||
using Print::write;
|
||||
//using HalSerial::write;
|
||||
|
||||
// public only for easy access by interrupt handlers
|
||||
static inline void handle_interrupt() __attribute__((__always_inline__));
|
||||
};
|
||||
|
||||
// Arduino 0012 workaround
|
||||
#undef int
|
||||
#undef char
|
||||
#undef long
|
||||
#undef byte
|
||||
#undef float
|
||||
#undef abs
|
||||
#undef round
|
||||
|
||||
#endif // SOFTWARESERIAL_H
|
Reference in New Issue
Block a user