[HAL][LPC176x] Pull out framework into separate repository

Framework and build platform now located at https://github.com/p3p/pio-framework-arduino-lpc176x and https://github.com/p3p/pio-nxplpc-arduino-lpc176x respectively

fix mkssbase leds

move hardware serial

remove hardware/software serial

Hardware Serial extraction

HardwareSerial ISRs

fix disabled serial2 causing Serial object to link

move usb devices out to framework

separate out adc/pwm peripheral function from hal.cpp

fix includes

remove unused pwm init

move adc

HAL header update

templated filtered adc

LPC1769 platform
This commit is contained in:
Christopher Pepper
2018-08-23 01:08:39 +01:00
parent 213e94bce2
commit 5ddf52d58e
139 changed files with 268 additions and 69800 deletions

View File

@ -1,125 +0,0 @@
/**
* 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 __ARDUINO_H__
#define __ARDUINO_H__
#include <stddef.h>
#include <stdint.h>
#include <math.h>
#include <pinmapping.h>
#define HIGH 0x01
#define LOW 0x00
#define INPUT 0x00
#define OUTPUT 0x01
#define INPUT_PULLUP 0x02
#define INPUT_PULLDOWN 0x03
#define LSBFIRST 0
#define MSBFIRST 1
#define CHANGE 0x02
#define FALLING 0x03
#define RISING 0x04
typedef uint8_t byte;
#define PROGMEM
#define PSTR(v) (v)
#define PGM_P const char *
// Used for libraries, preprocessor, and constants
#define min(a,b) ((a)<(b)?(a):(b))
#define max(a,b) ((a)>(b)?(a):(b))
#define abs(x) ((x)>0?(x):-(x))
#ifndef isnan
#define isnan std::isnan
#endif
#ifndef isinf
#define isinf std::isinf
#endif
#define sq(v) ((v) * (v))
#define square(v) sq(v)
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
//Interrupts
void cli(void); // Disable
void sei(void); // Enable
void attachInterrupt(const pin_t pin, void (*callback)(void), uint32_t mode);
void detachInterrupt(const pin_t pin);
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
// Program Memory
#define pgm_read_ptr(addr) (*((void**)(addr)))
#define pgm_read_byte_near(addr) (*((uint8_t*)(addr)))
#define pgm_read_float_near(addr) (*((float*)(addr)))
#define pgm_read_word_near(addr) (*((uint16_t*)(addr)))
#define pgm_read_dword_near(addr) (*((uint32_t*)(addr)))
#define pgm_read_byte(addr) pgm_read_byte_near(addr)
#define pgm_read_float(addr) pgm_read_float_near(addr)
#define pgm_read_word(addr) pgm_read_word_near(addr)
#define pgm_read_dword(addr) pgm_read_dword_near(addr)
#define memcpy_P memcpy
#define sprintf_P sprintf
#define strstr_P strstr
#define strncpy_P strncpy
#define vsnprintf_P vsnprintf
#define strcpy_P strcpy
#define snprintf_P snprintf
#define strlen_P strlen
#define strchr_P strchr
// Time functions
extern "C" {
void delay(const int milis);
}
void _delay_ms(const int delay);
void delayMicroseconds(unsigned long);
uint32_t millis();
//IO functions
void pinMode(const pin_t, const uint8_t);
void digitalWrite(pin_t, uint8_t);
bool digitalRead(pin_t);
void analogWrite(pin_t, int);
uint16_t analogRead(pin_t);
// EEPROM
void eeprom_write_byte(uint8_t *pos, unsigned char value);
uint8_t eeprom_read_byte(uint8_t *pos);
void eeprom_read_block (void *__dst, const void *__src, size_t __n);
void eeprom_update_block (const void *__src, void *__dst, size_t __n);
int32_t random(int32_t);
int32_t random(int32_t, int32_t);
void randomSeed(uint32_t);
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max);
#endif // __ARDUINO_DEF_H__

View File

@ -1,335 +0,0 @@
/**
* 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

View File

@ -1,91 +0,0 @@
/**
* 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_

View File

@ -1,329 +0,0 @@
/*
* 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 "../../shared/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

View File

@ -1,120 +0,0 @@
/*
* 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

View File

@ -1,219 +0,0 @@
/*
TwoWire.cpp - TWI/I2C library for Wiring & Arduino
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
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
*/
#ifdef TARGET_LPC1768
extern "C" {
#include <stdlib.h>
#include <string.h>
#include <inttypes.h>
#include <lpc17xx_i2c.h>
#include <lpc17xx_pinsel.h>
#include <lpc17xx_libcfg_default.h>
}
#include <Wire.h>
#define USEDI2CDEV_M 1
#if (USEDI2CDEV_M == 0)
#define I2CDEV_M LPC_I2C0
#elif (USEDI2CDEV_M == 1)
#define I2CDEV_M LPC_I2C1
#elif (USEDI2CDEV_M == 2)
#define I2CDEV_M LPC_I2C2
#else
#error "Master I2C device not defined!"
#endif
// Initialize Class Variables //////////////////////////////////////////////////
uint8_t TwoWire::rxBuffer[BUFFER_LENGTH];
uint8_t TwoWire::rxBufferIndex = 0;
uint8_t TwoWire::rxBufferLength = 0;
uint8_t TwoWire::txAddress = 0;
uint8_t TwoWire::txBuffer[BUFFER_LENGTH];
uint8_t TwoWire::txBufferIndex = 0;
uint8_t TwoWire::txBufferLength = 0;
uint8_t TwoWire::transmitting = 0;
// Constructors ////////////////////////////////////////////////////////////////
TwoWire::TwoWire() {
}
// Public Methods //////////////////////////////////////////////////////////////
void TwoWire::begin(void) {
rxBufferIndex = 0;
rxBufferLength = 0;
txBufferIndex = 0;
txBufferLength = 0;
/*
* Init I2C pin connect
*/
PINSEL_CFG_Type PinCfg;
PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
#if USEDI2CDEV_M == 0
PinCfg.Funcnum = 1;
PinCfg.Pinnum = 27;
PinCfg.Portnum = 0;
PINSEL_ConfigPin(&PinCfg); // SDA0 / D57 AUX-1
PinCfg.Pinnum = 28;
PINSEL_ConfigPin(&PinCfg); // SCL0 / D58 AUX-1
#endif
#if USEDI2CDEV_M == 1
PinCfg.Funcnum = 3;
PinCfg.Pinnum = 0;
PinCfg.Portnum = 0;
PINSEL_ConfigPin(&PinCfg); // SDA1 / D20 SCA
PinCfg.Pinnum = 1;
PINSEL_ConfigPin(&PinCfg); // SCL1 / D21 SCL
#endif
#if USEDI2CDEV_M == 2
PinCfg.Funcnum = 2;
PinCfg.Pinnum = 10;
PinCfg.Portnum = 0;
PINSEL_ConfigPin(&PinCfg); // SDA2 / D38 X_ENABLE_PIN
PinCfg.Pinnum = 11;
PINSEL_ConfigPin(&PinCfg); // SCL2 / D55 X_DIR_PIN
#endif
// Initialize I2C peripheral
I2C_Init(I2CDEV_M, 100000);
// Enable Master I2C operation
I2C_Cmd(I2CDEV_M, I2C_MASTER_MODE, ENABLE);
}
uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity) {
// clamp to buffer length
if (quantity > BUFFER_LENGTH)
quantity = BUFFER_LENGTH;
// perform blocking read into buffer
I2C_M_SETUP_Type transferMCfg;
transferMCfg.sl_addr7bit = address >> 1; // not sure about the right shift
transferMCfg.tx_data = NULL;
transferMCfg.tx_length = 0;
transferMCfg.rx_data = rxBuffer;
transferMCfg.rx_length = quantity;
transferMCfg.retransmissions_max = 3;
I2C_MasterTransferData(I2CDEV_M, &transferMCfg, I2C_TRANSFER_POLLING);
// set rx buffer iterator vars
rxBufferIndex = 0;
rxBufferLength = transferMCfg.rx_count;
return transferMCfg.rx_count;
}
uint8_t TwoWire::requestFrom(int address, int quantity) {
return requestFrom((uint8_t)address, (uint8_t)quantity);
}
void TwoWire::beginTransmission(uint8_t address) {
// indicate that we are transmitting
transmitting = 1;
// set address of targeted slave
txAddress = address;
// reset tx buffer iterator vars
txBufferIndex = 0;
txBufferLength = 0;
}
void TwoWire::beginTransmission(int address) {
beginTransmission((uint8_t)address);
}
uint8_t TwoWire::endTransmission(void) {
// transmit buffer (blocking)
I2C_M_SETUP_Type transferMCfg;
transferMCfg.sl_addr7bit = txAddress >> 1; // not sure about the right shift
transferMCfg.tx_data = txBuffer;
transferMCfg.tx_length = txBufferLength;
transferMCfg.rx_data = NULL;
transferMCfg.rx_length = 0;
transferMCfg.retransmissions_max = 3;
Status status = I2C_MasterTransferData(I2CDEV_M, &transferMCfg, I2C_TRANSFER_POLLING);
// reset tx buffer iterator vars
txBufferIndex = 0;
txBufferLength = 0;
// indicate that we are done transmitting
transmitting = 0;
return status == SUCCESS ? 0 : 4;
}
// must be called after beginTransmission(address)
size_t TwoWire::write(uint8_t data) {
if (transmitting) {
// don't bother if buffer is full
if (txBufferLength >= BUFFER_LENGTH) return 0;
// put byte in tx buffer
txBuffer[txBufferIndex++] = data;
// update amount in buffer
txBufferLength = txBufferIndex;
}
return 1;
}
// must be called after beginTransmission(address)
size_t TwoWire::write(const uint8_t *data, size_t quantity) {
size_t sent = 0;
if (transmitting)
for (sent = 0; sent < quantity; ++sent)
if (!write(data[sent])) break;
return sent;
}
// Must be called after requestFrom(address, numBytes)
int TwoWire::available(void) {
return rxBufferLength - rxBufferIndex;
}
// Must be called after requestFrom(address, numBytes)
int TwoWire::read(void) {
return rxBufferIndex < rxBufferLength ? rxBuffer[rxBufferIndex++] : -1;
}
// Must be called after requestFrom(address, numBytes)
int TwoWire::peek(void) {
return rxBufferIndex < rxBufferLength ? rxBuffer[rxBufferIndex] : -1;
}
// Preinstantiate Objects //////////////////////////////////////////////////////
TwoWire Wire = TwoWire();
#endif // TARGET_LPC1768

View File

@ -1,67 +0,0 @@
/**
* TwoWire.h - TWI/I2C library for Arduino & Wiring
* Copyright (c) 2006 Nicholas Zambetti. All right reserved.
*
* 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
*
* Modified 2012 by Todd Krein (todd@krein.org) to implement repeated starts
*/
#ifndef _TWOWIRE_H_
#define _TWOWIRE_H_
#include <inttypes.h>
#define BUFFER_LENGTH 32
class TwoWire {
private:
static uint8_t rxBuffer[];
static uint8_t rxBufferIndex;
static uint8_t rxBufferLength;
static uint8_t txAddress;
static uint8_t txBuffer[];
static uint8_t txBufferIndex;
static uint8_t txBufferLength;
static uint8_t transmitting;
public:
TwoWire();
void begin();
void beginTransmission(uint8_t);
void beginTransmission(int);
uint8_t endTransmission(void);
uint8_t endTransmission(uint8_t);
uint8_t requestFrom(uint8_t, uint8_t);
uint8_t requestFrom(int, int);
virtual size_t write(uint8_t);
virtual size_t write(const uint8_t *, size_t);
virtual int available(void);
virtual int read(void);
virtual int peek(void);
inline size_t write(unsigned long n) { return write((uint8_t)n); }
inline size_t write(long n) { return write((uint8_t)n); }
inline size_t write(unsigned int n) { return write((uint8_t)n); }
inline size_t write(int n) { return write((uint8_t)n); }
};
extern TwoWire Wire;
#endif // _TWOWIRE_H_

View File

@ -1,74 +0,0 @@
/**
* 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 <pinmapping.h>
#include "../../../gcode/parser.h"
// Get the digital pin for an analog index
pin_t analogInputToDigitalPin(const int8_t p) {
return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? adc_pin_table[p] : P_NC);
}
// Return the index of a pin number
// The pin number given here is in the form ppp:nnnnn
int16_t GET_PIN_MAP_INDEX(const pin_t pin) {
const uint16_t index = (LPC1768_PIN_PORT(pin) << 5) | LPC1768_PIN_PIN(pin);
return (index < NUM_DIGITAL_PINS && pin_map[index] != P_NC) ? index : -1;
}
// Test whether the pin is valid
bool VALID_PIN(const pin_t p) {
const int16_t ind = GET_PIN_MAP_INDEX(p);
return ind >= 0 && pin_map[ind] >= 0;
}
// Get the analog index for a digital pin
int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
return (VALID_PIN(p) ? LPC1768_PIN_ADC(p) : -1);
}
// Test whether the pin is PWM
bool PWM_PIN(const pin_t p) {
return VALID_PIN(p) && LPC1768_PIN_PWM(p);
}
// Test whether the pin is interruptable
bool INTERRUPT_PIN(const pin_t p) {
return VALID_PIN(p) && LPC1768_PIN_INTERRUPT(p);
}
// Get the pin number at the given index
pin_t GET_PIN_MAP_PIN(const int16_t ind) {
return WITHIN(ind, 0, NUM_DIGITAL_PINS - 1) ? pin_map[ind] : P_NC;
}
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
const uint16_t val = (uint16_t)parser.intval(code), port = val / 100, pin = val % 100;
const int16_t ind = (port < (NUM_DIGITAL_PINS >> 5) && (pin < 32))
? GET_PIN_MAP_INDEX(port << 5 | pin) : -2;
return ind > -2 ? ind : dval;
}
#endif // TARGET_LPC1768

View File

@ -1,294 +0,0 @@
/**
* 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 _PINMAPPING_H_
#define _PINMAPPING_H_
#include "../../../inc/MarlinConfigPre.h"
#include <stdint.h>
typedef int16_t pin_t;
#define PORT_0 000
#define PORT_1 001
#define PORT_2 010
#define PORT_3 011
#define PORT_4 100
#define PORT_(p) PORT_##p
#define PORT(p) PORT_(p)
#define PIN_0 00000
#define PIN_1 00001
#define PIN_2 00010
#define PIN_3 00011
#define PIN_4 00100
#define PIN_5 00101
#define PIN_6 00110
#define PIN_7 00111
#define PIN_8 01000
#define PIN_9 01001
#define PIN_10 01010
#define PIN_11 01011
#define PIN_12 01100
#define PIN_13 01101
#define PIN_14 01110
#define PIN_15 01111
#define PIN_16 10000
#define PIN_17 10001
#define PIN_18 10010
#define PIN_19 10011
#define PIN_20 10100
#define PIN_21 10101
#define PIN_22 10110
#define PIN_23 10111
#define PIN_24 11000
#define PIN_25 11001
#define PIN_26 11010
#define PIN_27 11011
#define PIN_28 11100
#define PIN_29 11101
#define PIN_30 11110
#define PIN_31 11111
#define PIN_(p) PIN_##p
#define PIN(p) PIN_(p)
#define ADC_NONE 0000
#define ADC_CHAN_0 0001
#define ADC_CHAN_1 0010
#define ADC_CHAN_2 0011
#define ADC_CHAN_3 0100
#define ADC_CHAN_4 0101
#define ADC_CHAN_5 0110
#define ADC_CHAN_6 0111
#define ADC_CHAN_7 1000
#define ADC_CHAN_(c) ADC_CHAN_##c
#define ADC_CHAN(p) ADC_CHAN_(p)
#define BOOL_0 0
#define BOOL_1 1
#define BOOL_(b) BOOL_##b
#define INTERRUPT(b) BOOL_(b)
#define PWM(b) BOOL_(b)
// Combine elements into pin bits: 0b00AAAAWIPPPNNNNN
#define LPC1768_PIN_(port, pin, int, pwm, adc) 0b00##adc##pwm##int##port##pin
#define LPC1768_PIN(port, pin, int, pwm, adc) LPC1768_PIN_(port, pin, int, pwm, adc)
constexpr uint8_t LPC1768_PIN_PORT(const pin_t pin) { return ((uint8_t)((pin >> 5) & 0b111)); }
constexpr uint8_t LPC1768_PIN_PIN(const pin_t pin) { return ((uint8_t)(pin & 0b11111)); }
constexpr bool LPC1768_PIN_INTERRUPT(const pin_t pin) { return (((pin >> 8) & 0b1) != 0); }
constexpr bool LPC1768_PIN_PWM(const pin_t pin) { return (((pin >> 9) & 0b1) != 0); }
constexpr int8_t LPC1768_PIN_ADC(const pin_t pin) { return (int8_t)((pin >> 10) & 0b1111) - 1; }
// ******************
// Runtime pinmapping
// ******************
#define P_NC -1
#if SERIAL_PORT != 3 && SERIAL_PORT_2 != 3
#define P0_00 LPC1768_PIN(PORT(0), PIN( 0), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_01 LPC1768_PIN(PORT(0), PIN( 1), INTERRUPT(1), PWM(0), ADC_NONE)
#endif
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
#define P0_02 LPC1768_PIN(PORT(0), PIN( 2), INTERRUPT(1), PWM(0), ADC_CHAN(7))
#define P0_03 LPC1768_PIN(PORT(0), PIN( 3), INTERRUPT(1), PWM(0), ADC_CHAN(6))
#endif
#define P0_04 LPC1768_PIN(PORT(0), PIN( 4), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_05 LPC1768_PIN(PORT(0), PIN( 5), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_06 LPC1768_PIN(PORT(0), PIN( 6), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_07 LPC1768_PIN(PORT(0), PIN( 7), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_08 LPC1768_PIN(PORT(0), PIN( 8), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_09 LPC1768_PIN(PORT(0), PIN( 9), INTERRUPT(1), PWM(0), ADC_NONE)
#if SERIAL_PORT != 2 && SERIAL_PORT_2 != 2
#define P0_10 LPC1768_PIN(PORT(0), PIN(10), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_11 LPC1768_PIN(PORT(0), PIN(11), INTERRUPT(1), PWM(0), ADC_NONE)
#endif
#if SERIAL_PORT != 1 && SERIAL_PORT_2 != 1
#define P0_15 LPC1768_PIN(PORT(0), PIN(15), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_16 LPC1768_PIN(PORT(0), PIN(16), INTERRUPT(1), PWM(0), ADC_NONE)
#endif
#define P0_17 LPC1768_PIN(PORT(0), PIN(17), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_18 LPC1768_PIN(PORT(0), PIN(18), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_19 LPC1768_PIN(PORT(0), PIN(19), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_20 LPC1768_PIN(PORT(0), PIN(20), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_21 LPC1768_PIN(PORT(0), PIN(21), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_22 LPC1768_PIN(PORT(0), PIN(22), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_23 LPC1768_PIN(PORT(0), PIN(23), INTERRUPT(1), PWM(0), ADC_CHAN(0))
#define P0_24 LPC1768_PIN(PORT(0), PIN(24), INTERRUPT(1), PWM(0), ADC_CHAN(1))
#define P0_25 LPC1768_PIN(PORT(0), PIN(25), INTERRUPT(1), PWM(0), ADC_CHAN(2))
#define P0_26 LPC1768_PIN(PORT(0), PIN(26), INTERRUPT(1), PWM(0), ADC_CHAN(3))
#define P0_27 LPC1768_PIN(PORT(0), PIN(27), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_28 LPC1768_PIN(PORT(0), PIN(28), INTERRUPT(1), PWM(0), ADC_NONE)
#if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
#define P0_29 LPC1768_PIN(PORT(0), PIN(29), INTERRUPT(1), PWM(0), ADC_NONE)
#define P0_30 LPC1768_PIN(PORT(0), PIN(30), INTERRUPT(1), PWM(0), ADC_NONE)
#endif
#define P1_00 LPC1768_PIN(PORT(1), PIN( 0), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_01 LPC1768_PIN(PORT(1), PIN( 1), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_04 LPC1768_PIN(PORT(1), PIN( 4), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_08 LPC1768_PIN(PORT(1), PIN( 8), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_09 LPC1768_PIN(PORT(1), PIN( 9), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_10 LPC1768_PIN(PORT(1), PIN(10), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_14 LPC1768_PIN(PORT(1), PIN(14), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_15 LPC1768_PIN(PORT(1), PIN(15), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_16 LPC1768_PIN(PORT(1), PIN(16), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_17 LPC1768_PIN(PORT(1), PIN(17), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_18 LPC1768_PIN(PORT(1), PIN(18), INTERRUPT(0), PWM(1), ADC_NONE)
#define P1_19 LPC1768_PIN(PORT(1), PIN(19), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_20 LPC1768_PIN(PORT(1), PIN(20), INTERRUPT(0), PWM(1), ADC_NONE)
#define P1_21 LPC1768_PIN(PORT(1), PIN(21), INTERRUPT(0), PWM(1), ADC_NONE)
#define P1_22 LPC1768_PIN(PORT(1), PIN(22), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_23 LPC1768_PIN(PORT(1), PIN(23), INTERRUPT(0), PWM(1), ADC_NONE)
#define P1_24 LPC1768_PIN(PORT(1), PIN(24), INTERRUPT(0), PWM(1), ADC_NONE)
#define P1_25 LPC1768_PIN(PORT(1), PIN(25), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_26 LPC1768_PIN(PORT(1), PIN(26), INTERRUPT(0), PWM(1), ADC_NONE)
#define P1_27 LPC1768_PIN(PORT(1), PIN(27), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_28 LPC1768_PIN(PORT(1), PIN(28), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_29 LPC1768_PIN(PORT(1), PIN(29), INTERRUPT(0), PWM(0), ADC_NONE)
#define P1_30 LPC1768_PIN(PORT(1), PIN(30), INTERRUPT(0), PWM(0), ADC_CHAN(4))
#define P1_31 LPC1768_PIN(PORT(1), PIN(31), INTERRUPT(0), PWM(0), ADC_CHAN(5))
#define P2_00 LPC1768_PIN(PORT(2), PIN( 0), INTERRUPT(1), PWM(1), ADC_NONE)
#define P2_01 LPC1768_PIN(PORT(2), PIN( 1), INTERRUPT(1), PWM(1), ADC_NONE)
#define P2_02 LPC1768_PIN(PORT(2), PIN( 2), INTERRUPT(1), PWM(1), ADC_NONE)
#define P2_03 LPC1768_PIN(PORT(2), PIN( 3), INTERRUPT(1), PWM(1), ADC_NONE)
#define P2_04 LPC1768_PIN(PORT(2), PIN( 4), INTERRUPT(1), PWM(1), ADC_NONE)
#define P2_05 LPC1768_PIN(PORT(2), PIN( 5), INTERRUPT(1), PWM(1), ADC_NONE)
#define P2_06 LPC1768_PIN(PORT(2), PIN( 6), INTERRUPT(1), PWM(0), ADC_NONE)
#define P2_07 LPC1768_PIN(PORT(2), PIN( 7), INTERRUPT(1), PWM(0), ADC_NONE)
#define P2_08 LPC1768_PIN(PORT(2), PIN( 8), INTERRUPT(1), PWM(0), ADC_NONE)
#define P2_09 LPC1768_PIN(PORT(2), PIN( 9), INTERRUPT(1), PWM(0), ADC_NONE)
#define P2_10 LPC1768_PIN(PORT(2), PIN(10), INTERRUPT(1), PWM(0), ADC_NONE)
#define P2_11 LPC1768_PIN(PORT(2), PIN(11), INTERRUPT(1), PWM(0), ADC_NONE)
#define P2_12 LPC1768_PIN(PORT(2), PIN(12), INTERRUPT(1), PWM(0), ADC_NONE)
#define P2_13 LPC1768_PIN(PORT(2), PIN(13), INTERRUPT(1), PWM(0), ADC_NONE)
#define P3_25 LPC1768_PIN(PORT(3), PIN(25), INTERRUPT(0), PWM(1), ADC_NONE)
#define P3_26 LPC1768_PIN(PORT(3), PIN(26), INTERRUPT(0), PWM(1), ADC_NONE)
#define P4_28 LPC1768_PIN(PORT(4), PIN(28), INTERRUPT(0), PWM(0), ADC_NONE)
#define P4_29 LPC1768_PIN(PORT(4), PIN(29), INTERRUPT(0), PWM(0), ADC_NONE)
// Pin index for M43 and M226
constexpr pin_t pin_map[] = {
#if SERIAL_PORT != 3 && SERIAL_PORT_2 != 3
P0_00, P0_01,
#else
P_NC, P_NC,
#endif
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
P0_02, P0_03,
#else
P_NC, P_NC,
#endif
P0_04, P0_05, P0_06, P0_07,
P0_08, P0_09,
#if SERIAL_PORT != 2 && SERIAL_PORT_2 != 2
P0_10, P0_11,
#else
P_NC, P_NC,
#endif
P_NC, P_NC, P_NC,
#if SERIAL_PORT != 1 && SERIAL_PORT_2 != 1
P0_15,
P0_16,
#else
P_NC,
P_NC,
#endif
P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23,
P0_24, P0_25, P0_26, P0_27, P0_28,
#if SERIAL_PORT != -1 && SERIAL_PORT_2 != -1
P0_29, P0_30,
#else
P_NC, P_NC,
#endif
P_NC,
P1_00, P1_01, P_NC, P_NC, P1_04, P_NC, P_NC, P_NC,
P1_08, P1_09, P1_10, P_NC, P_NC, P_NC, P1_14, P1_15,
P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23,
P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
P2_00, P2_01, P2_02, P2_03, P2_04, P2_05, P2_06, P2_07,
P2_08, P2_09, P2_10, P2_11, P2_12, P2_13, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P3_25, P3_26, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC, P_NC,
P_NC, P_NC, P_NC, P_NC, P4_28, P4_29, P_NC, P_NC
};
constexpr uint8_t NUM_DIGITAL_PINS = COUNT(pin_map);
constexpr pin_t adc_pin_table[] = {
P0_23, P0_24, P0_25, P0_26, P1_30, P1_31,
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
P0_03, P0_02
#endif
};
#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0
#define NUM_ANALOG_INPUTS 8
#else
#define NUM_ANALOG_INPUTS 6
#endif
// P0.6 thru P0.9 are for the onboard SD card
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
// Get the digital pin for an analog index
pin_t analogInputToDigitalPin(const int8_t p);
#define digitalPinToInterrupt(pin) (pin)
// Return the index of a pin number
// The pin number given here is in the form ppp:nnnnn
int16_t GET_PIN_MAP_INDEX(const pin_t pin);
// Test whether the pin is valid
bool VALID_PIN(const pin_t p);
// Get the analog index for a digital pin
int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p);
// Test whether the pin is PWM
bool PWM_PIN(const pin_t p);
// Test whether the pin is interruptable
bool INTERRUPT_PIN(const pin_t p);
#define LPC1768_PIN_INTERRUPT_M(pin) (((pin >> 8) & 0b1) != 0)
// Get the pin number at the given index
pin_t GET_PIN_MAP_PIN(const int16_t ind);
// Parse a G-code word into a pin index
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
#endif // _PINMAPPING_H_

View File

@ -1,161 +0,0 @@
/**
* 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 _HAL_SERIAL_H_
#define _HAL_SERIAL_H_
#include "../../../inc/MarlinConfigPre.h"
#if ENABLED(EMERGENCY_PARSER)
#include "../../../feature/emergency_parser.h"
#endif
#include <stdarg.h>
#include <stdio.h>
#include <Print.h>
/**
* Generic RingBuffer
* T type of the buffer array
* S size of the buffer (must be power of 2)
*/
template <typename T, uint32_t S> class RingBuffer {
public:
RingBuffer() {index_read = index_write = 0;}
uint32_t available() {return mask(index_write - index_read);}
uint32_t free() {return buffer_size - available();}
bool empty() {return index_read == index_write;}
bool full() {return next(index_write) == index_read;}
void clear() {index_read = index_write = 0;}
bool peek(T *const value) {
if (value == nullptr || empty()) return false;
*value = buffer[index_read];
return true;
}
uint32_t read(T *const value) {
if (value == nullptr || empty()) return 0;
*value = buffer[index_read];
index_read = next(index_read);
return 1;
}
uint32_t write(T value) {
uint32_t next_head = next(index_write);
if (next_head == index_read) return 0; // buffer full
buffer[index_write] = value;
index_write = next_head;
return 1;
}
private:
inline uint32_t mask(uint32_t val) {
return val & buffer_mask;
}
inline uint32_t next(uint32_t val) {
return mask(val + 1);
}
static const uint32_t buffer_size = S;
static const uint32_t buffer_mask = buffer_size - 1;
T buffer[buffer_size];
volatile uint32_t index_write;
volatile uint32_t index_read;
};
/**
* Serial Interface Class
* Data is injected directly into, and consumed from, the fifo buffers
*/
class HalSerial: public Print {
public:
#if ENABLED(EMERGENCY_PARSER)
EmergencyParser::State emergency_state;
#endif
HalSerial() : host_connected(false) { }
virtual ~HalSerial() { }
operator bool() { return host_connected; }
void begin(int32_t baud) { }
int16_t peek() {
uint8_t value;
return receive_buffer.peek(&value) ? value : -1;
}
int16_t read() {
uint8_t value;
return receive_buffer.read(&value) ? value : -1;
}
size_t write(const uint8_t c) {
if (!host_connected) return 0; // Do not fill buffer when host disconnected
while (transmit_buffer.write(c) == 0) { // Block until there is free room in buffer
if (!host_connected) return 0; // Break infinite loop on host disconect
}
return 1;
}
size_t available() {
return (size_t)receive_buffer.available();
}
void flush() {
receive_buffer.clear();
}
uint8_t availableForWrite(void) {
return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free();
}
void flushTX(void) {
while (transmit_buffer.available() && host_connected) { /* nada */}
}
size_t 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);
size_t i = 0;
if (length > 0 && length < 256) {
while (i < (size_t)length && host_connected) {
i += transmit_buffer.write(buffer[i]);
}
}
return i;
}
RingBuffer<uint8_t, 128> receive_buffer;
RingBuffer<uint8_t, 128> transmit_buffer;
volatile bool host_connected;
};
#endif // _HAL_SERIAL_H_