[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:
@ -22,8 +22,7 @@
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/Delay.h"
|
||||
|
||||
HalSerial usb_serial;
|
||||
#include "../../../gcode/parser.h"
|
||||
|
||||
// U8glib required functions
|
||||
extern "C" void u8g_xMicroDelay(uint16_t val) {
|
||||
@ -51,231 +50,11 @@ int freeMemory() {
|
||||
return result;
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// ADC
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define ADC_DONE 0x80000000
|
||||
#define ADC_OVERRUN 0x40000000
|
||||
|
||||
void HAL_adc_init(void) {
|
||||
LPC_SC->PCONP |= (1 << 12); // Enable CLOCK for internal ADC controller
|
||||
LPC_SC->PCLKSEL0 &= ~(0x3 << 24);
|
||||
LPC_SC->PCLKSEL0 |= (0x1 << 24); // 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to ADC clock divider
|
||||
LPC_ADC->ADCR = (0 << 0) // SEL: 0 = no channels selected
|
||||
| (0xFF << 8) // select slowest clock for A/D conversion 150 - 190 uS for a complete conversion
|
||||
| (0 << 16) // BURST: 0 = software control
|
||||
| (0 << 17) // CLKS: not applicable
|
||||
| (1 << 21) // PDN: 1 = operational
|
||||
| (0 << 24) // START: 0 = no start
|
||||
| (0 << 27); // EDGE: not applicable
|
||||
}
|
||||
|
||||
// externals need to make the call to KILL compile
|
||||
#include "../../core/language.h"
|
||||
|
||||
extern void kill(PGM_P);
|
||||
|
||||
void HAL_adc_enable_channel(int ch) {
|
||||
pin_t pin = analogInputToDigitalPin(ch);
|
||||
|
||||
if (pin == -1) {
|
||||
serial_error_start();
|
||||
SERIAL_PRINTF("INVALID ANALOG PORT:%d\n", ch);
|
||||
kill(MSG_KILLED);
|
||||
}
|
||||
|
||||
int8_t pin_port = LPC1768_PIN_PORT(pin),
|
||||
pin_port_pin = LPC1768_PIN_PIN(pin),
|
||||
pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
|
||||
uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 :
|
||||
pin_port == 0 ? 1 :
|
||||
pin_port == 1 ? 3 : 10;
|
||||
|
||||
switch (pin_sel_register) {
|
||||
case 1:
|
||||
LPC_PINCON->PINSEL1 &= ~(0x3 << pinsel_start_bit);
|
||||
LPC_PINCON->PINSEL1 |= (0x1 << pinsel_start_bit);
|
||||
break;
|
||||
case 3:
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << pinsel_start_bit);
|
||||
LPC_PINCON->PINSEL3 |= (0x3 << pinsel_start_bit);
|
||||
break;
|
||||
case 0:
|
||||
LPC_PINCON->PINSEL0 &= ~(0x3 << pinsel_start_bit);
|
||||
LPC_PINCON->PINSEL0 |= (0x2 << pinsel_start_bit);
|
||||
break;
|
||||
};
|
||||
}
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t ch) {
|
||||
if (analogInputToDigitalPin(ch) == -1) {
|
||||
SERIAL_PRINTF("HAL: HAL_adc_start_conversion: invalid channel %d\n", ch);
|
||||
return;
|
||||
}
|
||||
|
||||
LPC_ADC->ADCR &= ~0xFF; // Reset
|
||||
SBI(LPC_ADC->ADCR, ch); // Select Channel
|
||||
SBI(LPC_ADC->ADCR, 24); // Start conversion
|
||||
}
|
||||
|
||||
bool HAL_adc_finished(void) {
|
||||
return LPC_ADC->ADGDR & ADC_DONE;
|
||||
}
|
||||
|
||||
// possible config options if something similar is extended to more platforms.
|
||||
#define ADC_USE_MEDIAN_FILTER // Filter out erroneous readings
|
||||
#define ADC_MEDIAN_FILTER_SIZE 23 // Higher values increase step delay (phase shift),
|
||||
// (ADC_MEDIAN_FILTER_SIZE + 1) / 2 sample step delay (12 samples @ 500Hz: 24ms phase shift)
|
||||
// Memory usage per ADC channel (bytes): (6 * ADC_MEDIAN_FILTER_SIZE) + 16
|
||||
// 8 * ((6 * 23) + 16 ) = 1232 Bytes for 8 channels
|
||||
|
||||
#define ADC_USE_LOWPASS_FILTER // Filter out high frequency noise
|
||||
#define ADC_LOWPASS_K_VALUE 6 // Higher values increase rise time
|
||||
// Rise time sample delays for 100% signal convergence on full range step
|
||||
// (1 : 13, 2 : 32, 3 : 67, 4 : 139, 5 : 281, 6 : 565, 7 : 1135, 8 : 2273)
|
||||
// K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
|
||||
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
|
||||
|
||||
|
||||
// Sourced from https://embeddedgurus.com/stack-overflow/tag/median-filter/
|
||||
struct MedianFilter {
|
||||
#define STOPPER 0 // Smaller than any datum
|
||||
struct Pair {
|
||||
Pair *point; // Pointers forming list linked in sorted order
|
||||
uint16_t value; // Values to sort
|
||||
};
|
||||
|
||||
Pair buffer[ADC_MEDIAN_FILTER_SIZE] = {}; // Buffer of nwidth pairs
|
||||
Pair *datpoint = buffer; // Pointer into circular buffer of data
|
||||
Pair small = {NULL, STOPPER}; // Chain stopper
|
||||
Pair big = {&small, 0}; // Pointer to head (largest) of linked list.
|
||||
|
||||
uint16_t update(uint16_t datum) {
|
||||
Pair *successor; // Pointer to successor of replaced data item
|
||||
Pair *scan; // Pointer used to scan down the sorted list
|
||||
Pair *scanold; // Previous value of scan
|
||||
Pair *median; // Pointer to median
|
||||
uint16_t i;
|
||||
|
||||
if (datum == STOPPER) {
|
||||
datum = STOPPER + 1; // No stoppers allowed.
|
||||
}
|
||||
|
||||
if ( (++datpoint - buffer) >= (ADC_MEDIAN_FILTER_SIZE)) {
|
||||
datpoint = buffer; // Increment and wrap data in pointer.
|
||||
}
|
||||
|
||||
datpoint->value = datum; // Copy in new datum
|
||||
successor = datpoint->point; // Save pointer to old value's successor
|
||||
median = &big; // Median initially to first in chain
|
||||
scanold = NULL; // Scanold initially null.
|
||||
scan = &big; // Points to pointer to first (largest) datum in chain
|
||||
|
||||
// Handle chain-out of first item in chain as special case
|
||||
if (scan->point == datpoint) {
|
||||
scan->point = successor;
|
||||
}
|
||||
scanold = scan; // Save this pointer and
|
||||
scan = scan->point ; // step down chain
|
||||
|
||||
// Loop through the chain, normal loop exit via break.
|
||||
for (i = 0 ; i < ADC_MEDIAN_FILTER_SIZE; ++i) {
|
||||
// Handle odd-numbered item in chain
|
||||
if (scan->point == datpoint) {
|
||||
scan->point = successor; // Chain out the old datum
|
||||
}
|
||||
|
||||
if (scan->value < datum) { // If datum is larger than scanned value
|
||||
datpoint->point = scanold->point; // Chain it in here
|
||||
scanold->point = datpoint; // Mark it chained in
|
||||
datum = STOPPER;
|
||||
}
|
||||
|
||||
// Step median pointer down chain after doing odd-numbered element
|
||||
median = median->point; // Step median pointer
|
||||
if (scan == &small) {
|
||||
break; // Break at end of chain
|
||||
}
|
||||
scanold = scan; // Save this pointer and
|
||||
scan = scan->point; // step down chain
|
||||
|
||||
// Handle even-numbered item in chain.
|
||||
if (scan->point == datpoint) {
|
||||
scan->point = successor;
|
||||
}
|
||||
|
||||
if (scan->value < datum) {
|
||||
datpoint->point = scanold->point;
|
||||
scanold->point = datpoint;
|
||||
datum = STOPPER;
|
||||
}
|
||||
|
||||
if (scan == &small) {
|
||||
break;
|
||||
}
|
||||
|
||||
scanold = scan;
|
||||
scan = scan->point;
|
||||
}
|
||||
return median->value;
|
||||
}
|
||||
};
|
||||
|
||||
struct LowpassFilter {
|
||||
uint32_t data_delay = 0;
|
||||
uint16_t update(const uint16_t value) {
|
||||
data_delay -= (data_delay >> (ADC_LOWPASS_K_VALUE)) - value;
|
||||
return (uint16_t)(data_delay >> (ADC_LOWPASS_K_VALUE));
|
||||
}
|
||||
};
|
||||
|
||||
uint16_t HAL_adc_get_result(void) {
|
||||
uint32_t adgdr = LPC_ADC->ADGDR;
|
||||
CBI(LPC_ADC->ADCR, 24); // Stop conversion
|
||||
|
||||
if (adgdr & ADC_OVERRUN) return 0;
|
||||
uint16_t data = (adgdr >> 4) & 0xFFF; // copy the 12bit data value
|
||||
uint8_t adc_channel = (adgdr >> 24) & 0x7; // copy the 3bit used channel
|
||||
|
||||
#ifdef ADC_USE_MEDIAN_FILTER
|
||||
static MedianFilter median_filter[NUM_ANALOG_INPUTS];
|
||||
data = median_filter[adc_channel].update(data);
|
||||
#endif
|
||||
|
||||
#ifdef ADC_USE_LOWPASS_FILTER
|
||||
static LowpassFilter lowpass_filter[NUM_ANALOG_INPUTS];
|
||||
data = lowpass_filter[adc_channel].update(data);
|
||||
#endif
|
||||
|
||||
return ((data >> 2) & 0x3FF); // return 10bit value as Marlin expects
|
||||
}
|
||||
|
||||
#define SBIT_CNTEN 0
|
||||
#define SBIT_PWMEN 2
|
||||
#define SBIT_PWMMR0R 1
|
||||
|
||||
#define PWM_1 0 //P2_00 (0-1 Bits of PINSEL4)
|
||||
#define PWM_2 2 //P2_01 (2-3 Bits of PINSEL4)
|
||||
#define PWM_3 4 //P2_02 (4-5 Bits of PINSEL4)
|
||||
#define PWM_4 6 //P2_03 (6-7 Bits of PINSEL4)
|
||||
#define PWM_5 8 //P2_04 (8-9 Bits of PINSEL4)
|
||||
#define PWM_6 10 //P2_05 (10-11 Bits of PINSEL4)
|
||||
|
||||
void HAL_pwm_init(void) {
|
||||
LPC_PINCON->PINSEL4 = _BV(PWM_5) | _BV(PWM_6);
|
||||
|
||||
LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_PWMEN);
|
||||
LPC_PWM1->PR = 0x0; // No prescalar
|
||||
LPC_PWM1->MCR = _BV(SBIT_PWMMR0R); // Reset on PWMMR0, reset TC if it matches MR0
|
||||
LPC_PWM1->MR0 = 255; // set PWM cycle(Ton+Toff)=255)
|
||||
LPC_PWM1->MR5 = 0; // Set 50% Duty Cycle for the channels
|
||||
LPC_PWM1->MR6 = 0;
|
||||
|
||||
// Trigger the latch Enable Bits to load the new Match Values MR0, MR5, MR6
|
||||
LPC_PWM1->LER = _BV(0) | _BV(5) | _BV(6);
|
||||
// Enable the PWM output pins for PWM_5-PWM_6(P2_04 - P2_05)
|
||||
LPC_PWM1->PCR = _BV(13) | _BV(14);
|
||||
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
|
||||
|
@ -29,42 +29,27 @@
|
||||
#define _HAL_LPC1768_H_
|
||||
|
||||
#define CPU_32_BIT
|
||||
#define HAL_INIT
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
void HAL_init();
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
#undef min
|
||||
#undef max
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
void _printf (const char *format, ...);
|
||||
void _putc(uint8_t c);
|
||||
uint8_t _getc();
|
||||
|
||||
extern "C" volatile uint32_t _millis;
|
||||
|
||||
//arduino: Print.h
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
//arduino: binary.h (weird defines)
|
||||
#define B01 1
|
||||
#define B10 2
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <pinmapping.h>
|
||||
#include <CDCSerial.h>
|
||||
|
||||
#include "../shared/math_32bit.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
#include "fastio.h"
|
||||
#include <adc.h>
|
||||
#include "watchdog.h"
|
||||
#include "HAL_timers.h"
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
//
|
||||
// Default graphical display delays
|
||||
@ -79,32 +64,20 @@ extern "C" volatile uint32_t _millis;
|
||||
#define ST7920_DELAY_3 DELAY_NS(750)
|
||||
#endif
|
||||
|
||||
//
|
||||
// Arduino-style serial ports
|
||||
//
|
||||
#include "serial.h"
|
||||
#include "HardwareSerial.h"
|
||||
|
||||
extern HalSerial usb_serial;
|
||||
|
||||
#if !WITHIN(SERIAL_PORT, -1, 3)
|
||||
#error "SERIAL_PORT must be from -1 to 3"
|
||||
#endif
|
||||
|
||||
#if SERIAL_PORT == -1
|
||||
#define MYSERIAL0 usb_serial
|
||||
#define MYSERIAL0 UsbSerial
|
||||
#elif SERIAL_PORT == 0
|
||||
extern HardwareSerial Serial;
|
||||
#define MYSERIAL0 Serial
|
||||
#define MYSERIAL0 MSerial
|
||||
#elif SERIAL_PORT == 1
|
||||
extern HardwareSerial Serial1;
|
||||
#define MYSERIAL0 Serial1
|
||||
#define MYSERIAL0 MSerial1
|
||||
#elif SERIAL_PORT == 2
|
||||
extern HardwareSerial Serial2;
|
||||
#define MYSERIAL0 Serial2
|
||||
#define MYSERIAL0 MSerial2
|
||||
#elif SERIAL_PORT == 3
|
||||
#define MYSERIAL0 Serial3
|
||||
extern HardwareSerial Serial3;
|
||||
#define MYSERIAL0 MSerial3
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_PORT_2
|
||||
@ -115,19 +88,15 @@ extern HalSerial usb_serial;
|
||||
#endif
|
||||
#define NUM_SERIAL 2
|
||||
#if SERIAL_PORT_2 == -1
|
||||
#define MYSERIAL1 usb_serial
|
||||
#define MYSERIAL1 UsbSerial
|
||||
#elif SERIAL_PORT_2 == 0
|
||||
extern HardwareSerial Serial;
|
||||
#define MYSERIAL1 Serial
|
||||
#define MYSERIAL1 MSerial
|
||||
#elif SERIAL_PORT_2 == 1
|
||||
extern HardwareSerial Serial1;
|
||||
#define MYSERIAL1 Serial1
|
||||
#define MYSERIAL1 MSerial1
|
||||
#elif SERIAL_PORT_2 == 2
|
||||
extern HardwareSerial Serial2;
|
||||
#define MYSERIAL1 Serial2
|
||||
#define MYSERIAL1 MSerial2
|
||||
#elif SERIAL_PORT_2 == 3
|
||||
extern HardwareSerial Serial3;
|
||||
#define MYSERIAL1 Serial3
|
||||
#define MYSERIAL1 MSerial3
|
||||
#endif
|
||||
#else
|
||||
#define NUM_SERIAL 1
|
||||
@ -159,17 +128,28 @@ void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
|
||||
uint8_t spiRec(uint32_t chan);
|
||||
|
||||
//
|
||||
// ADC
|
||||
// ADC API
|
||||
//
|
||||
#define HAL_ANALOG_SELECT(pin) HAL_adc_enable_channel(pin)
|
||||
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
|
||||
#define HAL_READ_ADC() HAL_adc_get_result()
|
||||
#define HAL_ADC_READY() HAL_adc_finished()
|
||||
|
||||
void HAL_adc_init(void);
|
||||
void HAL_adc_enable_channel(int pin);
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
uint16_t HAL_adc_get_result(void);
|
||||
bool HAL_adc_finished(void);
|
||||
#define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift),
|
||||
// (ADC_MEDIAN_FILTER_SIZE + 1) / 2 sample step delay (12 samples @ 500Hz: 24ms phase shift)
|
||||
// Memory usage per ADC channel (bytes): (6 * ADC_MEDIAN_FILTER_SIZE) + 16
|
||||
// 8 * ((6 * 23) + 16 ) = 1232 Bytes for 8 channels
|
||||
|
||||
#define ADC_LOWPASS_K_VALUE (6) // Higher values increase rise time
|
||||
// Rise time sample delays for 100% signal convergence on full range step
|
||||
// (1 : 13, 2 : 32, 3 : 67, 4 : 139, 5 : 281, 6 : 565, 7 : 1135, 8 : 2273)
|
||||
// K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step
|
||||
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
|
||||
|
||||
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
|
||||
#define HAL_adc_init() FilteredADC::init()
|
||||
#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
|
||||
#define HAL_START_ADC(pin) FilteredADC::start_conversion(pin)
|
||||
#define HAL_READ_ADC() FilteredADC::get_result()
|
||||
#define HAL_ADC_READY() FilteredADC::finished_conversion()
|
||||
|
||||
// Parse a G-code word into a pin index
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
|
||||
|
||||
#endif // _HAL_LPC1768_H_
|
||||
|
@ -1 +0,0 @@
|
||||
// blank file needed until I get platformio to update it's copy of U8Glib-HAL
|
@ -20,9 +20,8 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* HAL for Arduino Due and compatible (SAM3X8E)
|
||||
*
|
||||
* For ARDUINO_ARCH_SAM
|
||||
* HAL For LPC1768
|
||||
*/
|
||||
|
||||
#ifndef _HAL_TIMERS_H
|
||||
|
@ -1,576 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2017 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The class Servo uses the PWM class to implement its functions
|
||||
*
|
||||
* All PWMs use the same repetition rate - 20mS because that's the normal servo rate
|
||||
*/
|
||||
|
||||
/**
|
||||
* This is a hybrid system.
|
||||
*
|
||||
* The PWM1 module is used to directly control the Servo 0, 1 & 3 pins and D9 & D10 pins. This keeps
|
||||
* the pulse width jitter to under a microsecond.
|
||||
*
|
||||
* For all other pins a timer is used to generate interrupts. The ISR
|
||||
* routine does the actual setting/clearing of pins. The upside is that any pin can
|
||||
* have a PWM channel assigned to it. The downside is that there is more pulse width
|
||||
* jitter. The jitter depends on what else is happening in the system and what ISRs
|
||||
* pre-empt the PWM ISR.
|
||||
*/
|
||||
|
||||
/**
|
||||
* The data structures are set up to minimize the computation done by the ISR which
|
||||
* minimizes ISR execution time. Execution times are 5-14µs depending on how full the
|
||||
* ISR table is. 14uS is for a 20 element ISR table.
|
||||
*
|
||||
* Two tables are used. One table contains the data used by the ISR to update/control
|
||||
* the PWM pins. The other is used as an aid when updating the ISR table.
|
||||
*
|
||||
* See the end of this file for details on the hardware/firmware interaction
|
||||
*/
|
||||
|
||||
/**
|
||||
* Directly controlled PWM pins (
|
||||
* NA means not being used as a directly controlled PWM pin
|
||||
*
|
||||
* Re-ARM MKS Sbase
|
||||
* PWM1.1 P1_18 SERVO3_PIN NA(no connection)
|
||||
* PWM1.1 P2_00 NA(E0_STEP_PIN) NA(X stepper)
|
||||
* PWM1.2 P1_20 SERVO0_PIN NA(no connection)
|
||||
* PWM1.2 P2_01 NA(X_STEP_PIN) NA(Y stepper)
|
||||
* PWM1.3 P1_21 SERVO1_PIN NA(no connection)
|
||||
* PWM1.3 P2_02 NA(Y_STEP_PIN) NA(Z stepper)
|
||||
* PWM1.4 P1_23 NA(SDSS(SSEL0)) SERVO0_PIN
|
||||
* PWM1.4 P2_03 NA(Z_STEP_PIN) NA(E0 stepper)
|
||||
* PWM1.5 P1_24 NA(X_MIN_PIN) NA(X_MIN_pin)
|
||||
* PWM1.5 P2_04 RAMPS_D9_PIN FAN_PIN
|
||||
* PWM1.6 P1_26 NA(Y_MIN_PIN) NA(Y_MIN_pin)
|
||||
* PWM1.6 P2_05 RAMPS_D10_PIN HEATER_BED_PIN
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include <lpc17xx_pinsel.h>
|
||||
#include "LPC1768_PWM.h"
|
||||
#include <Arduino.h>
|
||||
|
||||
#define NUM_ISR_PWMS 20
|
||||
|
||||
#define HAL_PWM_TIMER LPC_TIM3
|
||||
#define HAL_PWM_TIMER_ISR extern "C" void TIMER3_IRQHandler(void)
|
||||
#define HAL_PWM_TIMER_IRQn TIMER3_IRQn
|
||||
|
||||
#define LPC_PORT_OFFSET (0x0020)
|
||||
#define LPC_PIN(pin) (1UL << pin)
|
||||
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
|
||||
|
||||
typedef struct { // holds all data needed to control/init one of the PWM channels
|
||||
bool active_flag; // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
|
||||
pin_t pin;
|
||||
volatile uint32_t* set_register;
|
||||
volatile uint32_t* clr_register;
|
||||
uint32_t write_mask; // USED BY SET/CLEAR COMMANDS
|
||||
uint32_t microseconds; // value written to MR register
|
||||
uint32_t min; // lower value limit checked by WRITE routine before writing to the MR register
|
||||
uint32_t max; // upper value limit checked by WRITE routine before writing to the MR register
|
||||
uint8_t servo_index; // 0 - MAX_SERVO -1 : servo index, 0xFF : PWM channel
|
||||
} PWM_map;
|
||||
|
||||
PWM_map PWM1_map_A[NUM_ISR_PWMS]; // compiler will initialize to all zeros
|
||||
PWM_map PWM1_map_B[NUM_ISR_PWMS]; // compiler will initialize to all zeros
|
||||
|
||||
PWM_map *active_table = PWM1_map_A;
|
||||
PWM_map *work_table = PWM1_map_B;
|
||||
PWM_map *temp_table;
|
||||
|
||||
#define P1_18_PWM_channel 1 // servo 3
|
||||
#define P1_20_PWM_channel 2 // servo 0
|
||||
#define P1_21_PWM_channel 3 // servo 1
|
||||
#define P1_23_PWM_channel 4 // servo 0 for MKS Sbase
|
||||
#define P2_04_PWM_channel 5 // D9
|
||||
#define P2_05_PWM_channel 6 // D10
|
||||
|
||||
typedef struct {
|
||||
uint32_t min;
|
||||
uint32_t max;
|
||||
bool assigned;
|
||||
} table_direct;
|
||||
|
||||
table_direct direct_table[6]; // compiler will initialize to all zeros
|
||||
|
||||
/**
|
||||
* Prescale register and MR0 register values
|
||||
*
|
||||
* 100MHz PCLK 50MHz PCLK 25MHz PCLK 12.5MHz PCLK
|
||||
* ----------------- ----------------- ----------------- -----------------
|
||||
* desired prescale MR0 prescale MR0 prescale MR0 prescale MR0 resolution
|
||||
* prescale register register register register register register register register in degrees
|
||||
* freq value value value value value value value value
|
||||
*
|
||||
* 8 11.5 159,999 5.25 159,999 2.13 159,999 0.5625 159,999 0.023
|
||||
* 4 24 79,999 11.5 79,999 5.25 79,999 2.125 79,999 0.045
|
||||
* 2 49 39,999 24 39,999 11.5 39,999 5.25 39,999 0.090
|
||||
* 1 99 19,999 49 19,999 24 19,999 11.5 19,999 0.180
|
||||
* 0.5 199 9,999 99 9,999 49 9,999 24 9,999 0.360
|
||||
* 0.25 399 4,999 199 4,999 99 4,999 49 4,999 0.720
|
||||
* 0.125 799 2,499 399 2,499 199 2,499 99 2,499 1.440
|
||||
*
|
||||
* The desired prescale frequency column comes from an input in the range of 544 - 2400 microseconds
|
||||
* and the desire to just shift the input left or right as needed.
|
||||
*
|
||||
* A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
|
||||
* It also means we don't need to scale the input.
|
||||
*
|
||||
* The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
|
||||
* MR0 registers.
|
||||
*
|
||||
* Final settings:
|
||||
* PCLKSEL0: 0x0
|
||||
* PWM1PR: 0x018 (24)
|
||||
* PWM1MR0: 0x04E1F (19,999)
|
||||
*
|
||||
*/
|
||||
|
||||
void LPC1768_PWM_init(void) {
|
||||
|
||||
///// directly controlled PWM pins (interrupts not used for these)
|
||||
|
||||
#define SBIT_CNTEN 0 // PWM1 counter & pre-scaler enable/disable
|
||||
#define SBIT_CNTRST 1 // reset counters to known state
|
||||
#define SBIT_PWMEN 3 // 1 - PWM, 0 - timer
|
||||
#define SBIT_PWMMR0R 1
|
||||
#define PCPWM1 6
|
||||
#define PCLK_PWM1 12
|
||||
|
||||
SBI(LPC_SC->PCONP, PCPWM1); // Enable PWM1 controller (enabled on power up)
|
||||
LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
|
||||
LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
|
||||
|
||||
uint32_t PR = (CLKPWR_GetPCLK(CLKPWR_PCLKSEL_PWM1) / 1000000) - 1; // Prescalar to create 1 MHz output
|
||||
|
||||
LPC_PWM1->MR0 = LPC_PWM1_MR0; // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
|
||||
// MR0 must be set before TCR enables the PWM
|
||||
LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST) | _BV(SBIT_PWMEN); // Enable counters, reset counters, set mode to PWM
|
||||
CBI(LPC_PWM1->TCR, SBIT_CNTRST); // Take counters out of reset
|
||||
LPC_PWM1->PR = PR;
|
||||
LPC_PWM1->MCR = _BV(SBIT_PWMMR0R) | _BV(0); // Reset TC if it matches MR0, disable all interrupts except for MR0
|
||||
LPC_PWM1->CTCR = 0; // Disable counter mode (enable PWM mode)
|
||||
LPC_PWM1->LER = 0x07F; // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
|
||||
LPC_PWM1->PCR = 0; // Single edge mode for all channels, PWM1 control of outputs off
|
||||
|
||||
//// interrupt controlled PWM setup
|
||||
|
||||
LPC_SC->PCONP |= 1 << 23; // power on timer3
|
||||
HAL_PWM_TIMER->PR = PR;
|
||||
HAL_PWM_TIMER->MCR = 0x0B; // Interrupt on MR0 & MR1, reset on MR0
|
||||
HAL_PWM_TIMER->MR0 = LPC_PWM1_MR0;
|
||||
HAL_PWM_TIMER->MR1 = 0;
|
||||
HAL_PWM_TIMER->TCR = _BV(0); // enable
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
NVIC_SetPriority(HAL_PWM_TIMER_IRQn, NVIC_EncodePriority(0, 4, 0));
|
||||
}
|
||||
|
||||
|
||||
bool ISR_table_update = false; // flag to tell the ISR that the tables need to be updated & swapped
|
||||
uint8_t ISR_index = 0; // index used by ISR to skip already actioned entries
|
||||
#define COPY_ACTIVE_TABLE for (uint8_t i = 0; i < NUM_ISR_PWMS ; i++) work_table[i] = active_table[i]
|
||||
uint32_t first_MR1_value = LPC_PWM1_MR0 + 1;
|
||||
|
||||
void LPC1768_PWM_sort(void) {
|
||||
|
||||
for (uint8_t i = NUM_ISR_PWMS; --i;) { // (bubble) sort table by microseconds
|
||||
bool didSwap = false;
|
||||
PWM_map temp;
|
||||
for (uint16_t j = 0; j < i; ++j) {
|
||||
if (work_table[j].microseconds > work_table[j + 1].microseconds) {
|
||||
temp = work_table[j + 1];
|
||||
work_table[j + 1] = work_table[j];
|
||||
work_table[j] = temp;
|
||||
didSwap = true;
|
||||
}
|
||||
}
|
||||
if (!didSwap) break;
|
||||
}
|
||||
}
|
||||
|
||||
bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min /* = 1 */, uint32_t max /* = (LPC_PWM1_MR0 - 1) */, uint8_t servo_index /* = 0xFF */) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF)); // Sometimes the upper byte is garbled
|
||||
|
||||
//// direct control PWM code
|
||||
switch (pin) {
|
||||
case P1_23: // MKS Sbase Servo 0, PWM1 channel 4 (J3-8 PWM1.4)
|
||||
direct_table[P1_23_PWM_channel - 1].min = min;
|
||||
direct_table[P1_23_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_23_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
direct_table[P1_20_PWM_channel - 1].min = min;
|
||||
direct_table[P1_20_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_20_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
direct_table[P1_21_PWM_channel - 1].min = min;
|
||||
direct_table[P1_21_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_21_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
direct_table[P1_18_PWM_channel - 1].min = min;
|
||||
direct_table[P1_18_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P1_18_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P2_04: // D9 FET, PWM1 channel 5 (Pin 9 P2_04 PWM1.5)
|
||||
direct_table[P2_04_PWM_channel - 1].min = min;
|
||||
direct_table[P2_04_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P2_04_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
case P2_05: // D10 FET, PWM1 channel 6 (Pin 10 P2_05 PWM1.6)
|
||||
direct_table[P2_05_PWM_channel - 1].min = min;
|
||||
direct_table[P2_05_PWM_channel - 1].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
direct_table[P2_05_PWM_channel - 1].assigned = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
//// interrupt controlled PWM code
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn); // make it safe to update the active table
|
||||
// OK to update the active table because the
|
||||
// ISR doesn't use any of the changed items
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
if (ISR_table_update) //use work table if that's the newest
|
||||
temp_table = work_table;
|
||||
else
|
||||
temp_table = active_table;
|
||||
|
||||
uint8_t slot = 0;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // see if already in table
|
||||
if (temp_table[i].pin == pin) {
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return 1;
|
||||
}
|
||||
|
||||
for (uint8_t i = 1; (i < NUM_ISR_PWMS + 1) && !slot; i++) // find empty slot
|
||||
if ( !(temp_table[i - 1].set_register)) { slot = i; break; } // any item that can't be zero when active or just attached is OK
|
||||
|
||||
if (!slot) {
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return 0;
|
||||
}
|
||||
|
||||
slot--; // turn it into array index
|
||||
|
||||
temp_table[slot].pin = pin; // init slot
|
||||
temp_table[slot].set_register = &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET;
|
||||
temp_table[slot].clr_register = &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR;
|
||||
temp_table[slot].write_mask = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
temp_table[slot].min = min;
|
||||
temp_table[slot].max = max; // different max for ISR PWMs than for direct PWMs
|
||||
temp_table[slot].servo_index = servo_index;
|
||||
temp_table[slot].active_flag = false;
|
||||
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool LPC1768_PWM_detach_pin(pin_t pin) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
|
||||
|
||||
//// direct control PWM code
|
||||
switch (pin) {
|
||||
case P1_23: // MKS Sbase Servo 0, PWM1 channel 4 (J3-8 PWM1.4)
|
||||
if (!direct_table[P1_23_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_23_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 14); // return pin to general purpose I/O
|
||||
direct_table[P1_23_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
if (!direct_table[P1_20_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_20_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 8); // return pin to general purpose I/O
|
||||
direct_table[P1_20_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
if (!direct_table[P1_21_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_21_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 10); // return pin to general purpose I/O
|
||||
direct_table[P1_21_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
if (!direct_table[P1_18_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P1_18_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 4); // return pin to general purpose I/O
|
||||
direct_table[P1_18_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P2_04: // D9 FET, PWM1 channel 5 (Pin 9 P2_04 PWM1.5)
|
||||
if (!direct_table[P2_04_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P2_04_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 &= ~(0x3 << 10); // return pin to general purpose I/O
|
||||
direct_table[P2_04_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
case P2_05: // D10 FET, PWM1 channel 6 (Pin 10 P2_05 PWM1.6)
|
||||
if (!direct_table[P2_05_PWM_channel - 1].assigned) return false;
|
||||
CBI(LPC_PWM1->PCR, 8 + P2_05_PWM_channel); // disable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 &= ~(0x3 << 4); // return pin to general purpose I/O
|
||||
direct_table[P2_05_PWM_channel - 1].assigned = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
//// interrupt controlled PWM code
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
if (ISR_table_update) {
|
||||
ISR_table_update = false; // don't update yet - have another update to do
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
}
|
||||
else {
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
}
|
||||
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) { // find slot
|
||||
if (work_table[i].pin == pin) {
|
||||
slot = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (slot == 0xFF) // return error if pin not found
|
||||
return false;
|
||||
|
||||
work_table[slot] = {0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
LPC1768_PWM_sort(); // sort table by microseconds
|
||||
ISR_table_update = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// value is 0-20,000 microseconds (0% to 100% duty cycle)
|
||||
// servo routine provides values in the 544 - 2400 range
|
||||
bool LPC1768_PWM_write(pin_t pin, uint32_t value) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
|
||||
|
||||
//// direct control PWM code
|
||||
switch (pin) {
|
||||
case P1_23: // MKS Sbase Servo 0, PWM1 channel 4 (J3-8 PWM1.4)
|
||||
if (!direct_table[P1_23_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_23_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 = 0x2 << 14; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR4 = MAX(MIN(value, direct_table[P1_23_PWM_channel - 1].max), direct_table[P1_23_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_23_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
if (!direct_table[P1_20_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_20_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= 0x2 << 8; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR2 = MAX(MIN(value, direct_table[P1_20_PWM_channel - 1].max), direct_table[P1_20_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_20_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
if (!direct_table[P1_21_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_21_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= 0x2 << 10; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR3 = MAX(MIN(value, direct_table[P1_21_PWM_channel - 1].max), direct_table[P1_21_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_21_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
if (!direct_table[P1_18_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P1_18_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= 0x2 << 4; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR1 = MAX(MIN(value, direct_table[P1_18_PWM_channel - 1].max), direct_table[P1_18_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P1_18_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P2_04: // D9 FET, PWM1 channel 5 (Pin 9 P2_04 PWM1.5)
|
||||
if (!direct_table[P2_04_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P2_04_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 |= 0x1 << 8; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR5 = MAX(MIN(value, direct_table[P2_04_PWM_channel - 1].max), direct_table[P2_04_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P2_04_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
case P2_05: // D10 FET, PWM1 channel 6 (Pin 10 P2_05 PWM1.6)
|
||||
if (!direct_table[P2_05_PWM_channel - 1].assigned) return false;
|
||||
LPC_PWM1->PCR |= _BV(8 + P2_05_PWM_channel); // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL4 |= 0x1 << 10; // must set pin function AFTER setting PCR
|
||||
// load the new time value
|
||||
LPC_PWM1->MR6 = MAX(MIN(value, direct_table[P2_05_PWM_channel - 1].max), direct_table[P2_05_PWM_channel - 1].min);
|
||||
LPC_PWM1->LER = 0x1 << P2_05_PWM_channel; // Set the latch Enable Bit to load the new Match Value on the next MR0
|
||||
return true;
|
||||
}
|
||||
|
||||
//// interrupt controlled PWM code
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
if (!ISR_table_update) // use the most up to date table
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // find slot
|
||||
if (work_table[i].pin == pin) { slot = i; break; }
|
||||
if (slot == 0xFF) { // return error if pin not found
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
return false;
|
||||
}
|
||||
|
||||
work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);;
|
||||
work_table[slot].active_flag = true;
|
||||
|
||||
LPC1768_PWM_sort(); // sort table by microseconds
|
||||
ISR_table_update = true;
|
||||
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool useable_hardware_PWM(pin_t pin) {
|
||||
|
||||
pin = GET_PIN_MAP_PIN(GET_PIN_MAP_INDEX(pin & 0xFF));
|
||||
|
||||
NVIC_DisableIRQ(HAL_PWM_TIMER_IRQn);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
|
||||
bool return_flag = false;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // see if it's already setup
|
||||
if (active_table[i].pin == pin) return_flag = true;
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) // see if there is an empty slot
|
||||
if (!active_table[i].set_register) return_flag = true;
|
||||
NVIC_EnableIRQ(HAL_PWM_TIMER_IRQn); // re-enable PWM interrupts
|
||||
return return_flag;
|
||||
}
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
#define PWM_LPC1768_ISR_SAFETY_FACTOR 5 // amount of time needed to guarantee MR1 count will be above TC
|
||||
volatile bool in_PWM_isr = false;
|
||||
|
||||
HAL_PWM_TIMER_ISR {
|
||||
bool first_active_entry = true;
|
||||
uint32_t next_MR1_val;
|
||||
|
||||
if (in_PWM_isr) goto exit_PWM_ISR; // prevent re-entering this ISR
|
||||
in_PWM_isr = true;
|
||||
|
||||
if (HAL_PWM_TIMER->IR & 0x01) { // MR0 interrupt
|
||||
next_MR1_val = first_MR1_value; // only used if have a blank ISR table
|
||||
if (ISR_table_update) { // new values have been loaded so swap tables
|
||||
temp_table = active_table;
|
||||
active_table = work_table;
|
||||
work_table = temp_table;
|
||||
ISR_table_update = false;
|
||||
}
|
||||
}
|
||||
HAL_PWM_TIMER->IR = 0x3F; // clear all interrupts
|
||||
|
||||
for (uint8_t i = 0; i < NUM_ISR_PWMS; i++) {
|
||||
if (active_table[i].active_flag) {
|
||||
if (first_active_entry) {
|
||||
first_active_entry = false;
|
||||
next_MR1_val = active_table[i].microseconds;
|
||||
}
|
||||
if (HAL_PWM_TIMER->TC < active_table[i].microseconds) {
|
||||
*active_table[i].set_register = active_table[i].write_mask; // set pin high
|
||||
}
|
||||
else {
|
||||
*active_table[i].clr_register = active_table[i].write_mask; // set pin low
|
||||
next_MR1_val = (i == NUM_ISR_PWMS -1)
|
||||
? LPC_PWM1_MR0 + 1 // done with table, wait for MR0
|
||||
: active_table[i + 1].microseconds; // set next MR1 interrupt?
|
||||
}
|
||||
}
|
||||
}
|
||||
if (first_active_entry) next_MR1_val = LPC_PWM1_MR0 + 1; // empty table so disable MR1 interrupt
|
||||
HAL_PWM_TIMER->MR1 = MAX(next_MR1_val, HAL_PWM_TIMER->TC + PWM_LPC1768_ISR_SAFETY_FACTOR); // set next
|
||||
in_PWM_isr = false;
|
||||
|
||||
exit_PWM_ISR:
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
///////////////// HARDWARE FIRMWARE INTERACTION ////////////////
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
/**
|
||||
* There are two distinct systems used for PWMs:
|
||||
* directly controlled pins
|
||||
* ISR controlled pins.
|
||||
*
|
||||
* The two systems are independent of each other. The use the same counter frequency so there's no
|
||||
* translation needed when setting the time values. The init, attach, detach and write routines all
|
||||
* start with the direct pin code which is followed by the ISR pin code.
|
||||
*
|
||||
* The PMW1 module handles the directly controlled pins. Each directly controlled pin is associated
|
||||
* with a match register (MR1 - MR6). When the associated MR equals the module's TIMER/COUNTER (TC)
|
||||
* then the pins is set to low. The MR0 register controls the repetition rate. When the TC equals
|
||||
* MR0 then the TC is reset and ALL directly controlled pins are set high. The resulting pulse widths
|
||||
* are almost immune to system loading and ISRs. No PWM1 interrupts are used.
|
||||
*
|
||||
* The ISR controlled pins use the TIMER/COUNTER, MR0 and MR1 registers from one timer. MR0 controls
|
||||
* period of the controls the repetition rate. When the TC equals MR0 then the TC is reset and an
|
||||
* interrupt is generated. When the TC equals MR1 then an interrupt is generated.
|
||||
*
|
||||
* Each interrupt does the following:
|
||||
* 1) Swaps the tables if it's a MR0 interrupt and the swap flag is set. It then clears the swap flag.
|
||||
* 2) Scans the entire ISR table (it's been sorted low to high time)
|
||||
* a. If its the first active entry then it grabs the time as a tentative time for MR1
|
||||
* b. If active and TC is less than the time then it sets the pin high
|
||||
* c. If active and TC is more than the time it sets the pin high
|
||||
* d. On every entry that sets a pin low it grabs the NEXT entry's time for use as the next MR1.
|
||||
* This results in MR1 being set to the time in the first active entry that does NOT set a
|
||||
* pin low.
|
||||
* e. If it's setting the last entry's pin low then it sets MR1 to a value bigger than MR0
|
||||
* f. If no value has been grabbed for the next MR1 then it's an empty table and MR1 is set to a
|
||||
* value greater than MR0
|
||||
*/
|
@ -1,79 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2017 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The class Servo uses the PWM class to implement its functions
|
||||
*
|
||||
* All PWMs use the same repetition rate - 20mS because that's the normal servo rate
|
||||
*/
|
||||
|
||||
/**
|
||||
* This is a hybrid system.
|
||||
*
|
||||
* The PWM1 module is used to directly control the Servo 0, 1 & 3 pins. This keeps
|
||||
* the pulse width jitter to under a microsecond.
|
||||
*
|
||||
* For all other pins the PWM1 module is used to generate interrupts. The ISR
|
||||
* routine does the actual setting/clearing of pins. The upside is that any pin can
|
||||
* have a PWM channel assigned to it. The downside is that there is more pulse width
|
||||
* jitter. The jitter depends on what else is happening in the system and what ISRs
|
||||
* prempt the PWM ISR. Writing to the SD card can add 20 microseconds to the pulse
|
||||
* width.
|
||||
*/
|
||||
|
||||
/**
|
||||
* The data structures are setup to minimize the computation done by the ISR which
|
||||
* minimizes ISR execution time. Execution times are 2.2 - 3.7 microseconds.
|
||||
*
|
||||
* Two tables are used. active_table is used by the ISR. Changes to the table are
|
||||
* are done by copying the active_table into the work_table, updating the work_table
|
||||
* and then swapping the two tables. Swapping is done by manipulating pointers.
|
||||
*
|
||||
* Immediately after the swap the ISR uses the work_table until the start of the
|
||||
* next 20mS cycle. During this transition the "work_table" is actually the table
|
||||
* that was being used before the swap. The "active_table" contains the data that
|
||||
* will start being used at the start of the next 20mS period. This keeps the pins
|
||||
* well behaved during the transition.
|
||||
*
|
||||
* The ISR's priority is set to the maximum otherwise other ISRs can cause considerable
|
||||
* jitter in the PWM high time.
|
||||
*
|
||||
* See the end of this file for details on the hardware/firmware interaction
|
||||
*/
|
||||
|
||||
#ifndef _LPC1768_PWM_H_
|
||||
#define _LPC1768_PWM_H_
|
||||
|
||||
#include <pinmapping.h>
|
||||
#include <lpc17xx_clkpwr.h>
|
||||
|
||||
#define LPC_PWM1_MR0 19999 // base repetition rate minus one count - 20mS
|
||||
#define LPC_PWM1_PCLKSEL0 CLKPWR_PCLKSEL_CCLK_DIV_4 // select clock divider for prescaler - defaults to 4 on power up
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
void LPC1768_PWM_init(void);
|
||||
bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min=1, uint32_t max=(LPC_PWM1_MR0 - (MR0_MARGIN)), uint8_t servo_index=0xFF);
|
||||
bool LPC1768_PWM_write(pin_t pin, uint32_t value);
|
||||
bool LPC1768_PWM_detach_pin(pin_t pin);
|
||||
bool useable_hardware_PWM(pin_t pin);
|
||||
|
||||
#endif // _LPC1768_PWM_H_
|
@ -1,163 +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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Based on servo.cpp - Interrupt driven Servo library for Arduino using 16 bit
|
||||
* timers- Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
|
||||
*/
|
||||
|
||||
/**
|
||||
* A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
|
||||
* The servos are pulsed in the background using the value most recently written using the write() method
|
||||
*
|
||||
* Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
|
||||
* Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
|
||||
*
|
||||
* The methods are:
|
||||
*
|
||||
* Servo - Class for manipulating servo motors connected to Arduino pins.
|
||||
*
|
||||
* attach(pin) - Attach a servo motor to an i/o pin.
|
||||
* attach(pin, min, max) - Attach to a pin, setting min and max values in microseconds
|
||||
* Default min is 544, max is 2400
|
||||
*
|
||||
* write() - Set the servo angle in degrees. (Invalid angles —over MIN_PULSE_WIDTH— are treated as µs.)
|
||||
* writeMicroseconds() - Set the servo pulse width in microseconds.
|
||||
* move(pin, angle) - Sequence of attach(pin), write(angle), safe_delay(servo_delay[servoIndex]).
|
||||
* With DEACTIVATE_SERVOS_AFTER_MOVE it detaches after servo_delay[servoIndex].
|
||||
* read() - Get the last-written servo pulse width as an angle between 0 and 180.
|
||||
* readMicroseconds() - Get the last-written servo pulse width in microseconds.
|
||||
* attached() - Return true if a servo is attached.
|
||||
* detach() - Stop an attached servo from pulsing its i/o pin.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The only time that this library wants physical movement is when a WRITE
|
||||
* command is issued. Before that all the attach & detach activity is solely
|
||||
* within the data base.
|
||||
*
|
||||
* The PWM output is inactive until the first WRITE. After that it stays active
|
||||
* unless DEACTIVATE_SERVOS_AFTER_MOVE is enabled and a MOVE command was issued.
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SERVOS
|
||||
|
||||
#include "LPC1768_PWM.h"
|
||||
#include "LPC1768_Servo.h"
|
||||
#include "servo_private.h"
|
||||
|
||||
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
|
||||
uint8_t ServoCount = 0; // the total number of attached servos
|
||||
|
||||
#define US_TO_PULSE_WIDTH(p) p
|
||||
#define PULSE_WIDTH_TO_US(p) p
|
||||
#define TRIM_DURATION 0
|
||||
#define SERVO_MIN() MIN_PULSE_WIDTH // minimum value in uS for this servo
|
||||
#define SERVO_MAX() MAX_PULSE_WIDTH // maximum value in uS for this servo
|
||||
|
||||
Servo::Servo() {
|
||||
if (ServoCount < MAX_SERVOS) {
|
||||
this->servoIndex = ServoCount++; // assign a servo index to this instance
|
||||
servo_info[this->servoIndex].pulse_width = US_TO_PULSE_WIDTH(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
|
||||
}
|
||||
else
|
||||
this->servoIndex = INVALID_SERVO; // too many servos
|
||||
}
|
||||
|
||||
int8_t Servo::attach(const int pin) {
|
||||
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
|
||||
}
|
||||
|
||||
int8_t Servo::attach(const int pin, const int min, const int max) {
|
||||
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
|
||||
if (pin > 0) servo_info[this->servoIndex].Pin.nbr = pin; // only assign a pin value if the pin info is
|
||||
// greater than zero. This way the init routine can
|
||||
// assign the pin and the MOVE command only needs the value.
|
||||
|
||||
this->min = MIN_PULSE_WIDTH; //resolution of min/max is 1 uS
|
||||
this->max = MAX_PULSE_WIDTH;
|
||||
|
||||
servo_info[this->servoIndex].Pin.isActive = true;
|
||||
|
||||
return this->servoIndex;
|
||||
}
|
||||
|
||||
void Servo::detach() {
|
||||
servo_info[this->servoIndex].Pin.isActive = false;
|
||||
}
|
||||
|
||||
void Servo::write(int value) {
|
||||
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());
|
||||
// odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says
|
||||
// zero degrees should be 500 microseconds and 180 should be 2500
|
||||
}
|
||||
this->writeMicroseconds(value);
|
||||
}
|
||||
|
||||
void Servo::writeMicroseconds(int value) {
|
||||
// calculate and store the values for the given channel
|
||||
byte channel = this->servoIndex;
|
||||
if (channel < MAX_SERVOS) { // ensure channel is valid
|
||||
// ensure pulse width is valid
|
||||
value = constrain(value, SERVO_MIN(), SERVO_MAX()) - (TRIM_DURATION);
|
||||
value = US_TO_PULSE_WIDTH(value); // convert to pulse_width after compensating for interrupt overhead - 12 Aug 2009
|
||||
|
||||
servo_info[channel].pulse_width = value;
|
||||
LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex);
|
||||
LPC1768_PWM_write(servo_info[this->servoIndex].Pin.nbr, value);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// return the value as degrees
|
||||
int Servo::read() { return map(this->readMicroseconds() + 1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
|
||||
|
||||
int Servo::readMicroseconds() {
|
||||
return (this->servoIndex == INVALID_SERVO) ? 0 : PULSE_WIDTH_TO_US(servo_info[this->servoIndex].pulse_width) + TRIM_DURATION;
|
||||
}
|
||||
|
||||
bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; }
|
||||
|
||||
void Servo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) { // notice the pin number is zero here
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
LPC1768_PWM_detach_pin(servo_info[this->servoIndex].Pin.nbr); // shut down the PWM signal
|
||||
LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex); // make sure no one else steals the slot
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAS_SERVOS
|
||||
#endif // TARGET_LPC1768
|
@ -1,62 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2017 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The class Servo uses the PWM class to implement its functions
|
||||
*
|
||||
* The PWM1 module is only used to generate interrups at specified times. It
|
||||
* is NOT used to directly toggle pins. The ISR writes to the pin assigned to
|
||||
* that interrupt
|
||||
*
|
||||
* All PWMs use the same repetition rate - 20mS because that's the normal servo rate
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef LPC1768_SERVO_H
|
||||
#define LPC1768_SERVO_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
class Servo {
|
||||
public:
|
||||
Servo();
|
||||
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(const int pin, const int min, const int max); // as above but also sets min and max values for writes.
|
||||
void detach();
|
||||
void write(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 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 DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
|
||||
int read(); // returns current pulse width as an angle between 0 and 180 degrees
|
||||
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
|
||||
bool attached(); // return true if this servo is attached, otherwise false
|
||||
|
||||
private:
|
||||
uint8_t servoIndex; // index into the channel data for this servo
|
||||
int min;
|
||||
int max;
|
||||
};
|
||||
|
||||
#define HAL_SERVO_LIB Servo
|
||||
|
||||
#endif // LPC1768_SERVO_H
|
56
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp
Normal file
56
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp
Normal file
@ -0,0 +1,56 @@
|
||||
/**
|
||||
* 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 "../../inc/MarlinConfigPre.h"
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0)
|
||||
MarlinSerial MSerial(LPC_UART0);
|
||||
extern "C" void UART0_IRQHandler(void) {
|
||||
MSerial.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 1) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 1)
|
||||
MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
|
||||
extern "C" void UART1_IRQHandler(void) {
|
||||
MSerial1.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 2) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 2)
|
||||
MarlinSerial MSerial2(LPC_UART2);
|
||||
extern "C" void UART2_IRQHandler(void) {
|
||||
MSerial2.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if (defined(SERIAL_PORT) && SERIAL_PORT == 3) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 3)
|
||||
MarlinSerial MSerial3(LPC_UART3);
|
||||
extern "C" void UART3_IRQHandler(void) {
|
||||
MSerial3.IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TARGET_LPC1768
|
71
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h
Normal file
71
Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h
Normal file
@ -0,0 +1,71 @@
|
||||
/**
|
||||
* 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 MARLINSERIAL_H
|
||||
#define MARLINSERIAL_H
|
||||
#include <HardwareSerial.h>
|
||||
#include <WString.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/emergency_parser.h"
|
||||
#endif
|
||||
|
||||
#ifndef SERIAL_PORT
|
||||
#define SERIAL_PORT 0
|
||||
#endif
|
||||
|
||||
#ifndef RX_BUFFER_SIZE
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#ifndef TX_BUFFER_SIZE
|
||||
#define TX_BUFFER_SIZE 32
|
||||
#endif
|
||||
|
||||
class MarlinSerial : public HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE> {
|
||||
public:
|
||||
MarlinSerial(LPC_UART_TypeDef *UARTx) :
|
||||
HardwareSerial<RX_BUFFER_SIZE, TX_BUFFER_SIZE>(UARTx)
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
, emergency_state(EmergencyParser::State::EP_RESET)
|
||||
#endif
|
||||
{
|
||||
}
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
bool recv_callback(const char c) override {
|
||||
emergency_parser.update(emergency_state, c);
|
||||
return true; // do not discard character
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
EmergencyParser::State emergency_state;
|
||||
#endif
|
||||
};
|
||||
|
||||
extern MarlinSerial MSerial;
|
||||
extern MarlinSerial MSerial1;
|
||||
extern MarlinSerial MSerial2;
|
||||
extern MarlinSerial MSerial3;
|
||||
|
||||
#endif // MARLINSERIAL_H
|
@ -1,90 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016, 2017 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/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Software SPI functions originally from Arduino Sd2Card Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*/
|
||||
|
||||
/**
|
||||
* For TARGET_LPC1768
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Software SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* This software SPI runs at multiple rates. The SD software provides an index
|
||||
* (spiRate) of 0-6. The mapping is:
|
||||
* 0 - about 5 MHz peak (6 MHz on LPC1769)
|
||||
* 1-2 - about 2 MHz peak
|
||||
* 3 - about 1 MHz peak
|
||||
* 4 - about 500 kHz peak
|
||||
* 5 - about 250 kHz peak
|
||||
* 6 - about 125 kHz peak
|
||||
*/
|
||||
|
||||
uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) {
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
if (spi_speed == 0) {
|
||||
WRITE(mosi_pin, !!(b & 0x80));
|
||||
WRITE(sck_pin, HIGH);
|
||||
b <<= 1;
|
||||
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
|
||||
WRITE(sck_pin, LOW);
|
||||
}
|
||||
else {
|
||||
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
||||
for (uint8_t j = 0; j < spi_speed; j++)
|
||||
WRITE(mosi_pin, state);
|
||||
|
||||
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
|
||||
WRITE(sck_pin, HIGH);
|
||||
|
||||
b <<= 1;
|
||||
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
|
||||
|
||||
for (uint8_t j = 0; j < spi_speed; j++)
|
||||
WRITE(sck_pin, LOW);
|
||||
}
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
void swSpiBegin(const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) {
|
||||
SET_OUTPUT(sck_pin);
|
||||
if (VALID_PIN(miso_pin)) SET_INPUT(miso_pin);
|
||||
SET_OUTPUT(mosi_pin);
|
||||
}
|
||||
|
||||
uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) {
|
||||
WRITE(mosi_pin, HIGH);
|
||||
WRITE(sck_pin, LOW);
|
||||
return (SystemCoreClock == 120000000 ? 44 : 38) / POW(2, 6 - MIN(spiRate, 6));
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
@ -1,50 +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 _SOFTWARE_SPI_H_
|
||||
#define _SOFTWARE_SPI_H_
|
||||
|
||||
#include <pinmapping.h>
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Software SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* This software SPI runs at multiple rates. The SD software provides an index
|
||||
* (spiRate) of 0-6. The mapping is:
|
||||
* 0 - about 5 MHz peak (6 MHz on LPC1769)
|
||||
* 1-2 - about 2 MHz peak
|
||||
* 3 - about 1 MHz peak
|
||||
* 4 - about 500 kHz peak
|
||||
* 5 - about 250 kHz peak
|
||||
* 6 - about 125 kHz peak
|
||||
*/
|
||||
|
||||
void swSpiBegin(const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin);
|
||||
|
||||
// Returns the spi_speed value to be passed to swSpiTransfer
|
||||
uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin);
|
||||
|
||||
uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin);
|
||||
|
||||
#endif // _SOFTWARE_SPI_H_
|
@ -1,162 +0,0 @@
|
||||
/**
|
||||
* Copyright (c) 2011-2012 Arduino. 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
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#define GNUM 31
|
||||
|
||||
typedef void (*interruptCB)(void);
|
||||
|
||||
static interruptCB callbacksP0[GNUM] = {};
|
||||
static interruptCB callbacksP2[GNUM] = {};
|
||||
|
||||
extern "C" void GpioEnableInt(const uint32_t port, const uint32_t pin, const uint32_t mode);
|
||||
extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin);
|
||||
|
||||
|
||||
static void __initialize() {
|
||||
NVIC_SetPriority(EINT3_IRQn, NVIC_EncodePriority(0, 1, 0));
|
||||
NVIC_EnableIRQ(EINT3_IRQn);
|
||||
}
|
||||
|
||||
void attachInterrupt(const pin_t pin, void (*callback)(void), uint32_t mode) {
|
||||
static int enabled = 0;
|
||||
|
||||
if (!INTERRUPT_PIN(pin)) return;
|
||||
|
||||
if (!enabled) {
|
||||
__initialize();
|
||||
++enabled;
|
||||
}
|
||||
|
||||
uint8_t myport = LPC1768_PIN_PORT(pin),
|
||||
mypin = LPC1768_PIN_PIN(pin);
|
||||
|
||||
if (myport == 0)
|
||||
callbacksP0[mypin] = callback;
|
||||
else
|
||||
callbacksP2[mypin] = callback;
|
||||
|
||||
// Enable interrupt
|
||||
GpioEnableInt(myport,mypin,mode);
|
||||
}
|
||||
|
||||
void detachInterrupt(const pin_t pin) {
|
||||
if (!INTERRUPT_PIN(pin)) return;
|
||||
|
||||
const uint8_t myport = LPC1768_PIN_PORT(pin),
|
||||
mypin = LPC1768_PIN_PIN(pin);
|
||||
|
||||
// Disable interrupt
|
||||
GpioDisableInt(myport, mypin);
|
||||
|
||||
// unset callback
|
||||
if (myport == 0)
|
||||
callbacksP0[mypin] = 0;
|
||||
else //if (myport == 2 )
|
||||
callbacksP2[mypin] = 0;
|
||||
}
|
||||
|
||||
|
||||
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode) {
|
||||
//pin here is the processor pin, not logical pin
|
||||
if (port == 0) {
|
||||
LPC_GPIOINT->IO0IntClr = _BV(pin);
|
||||
if (mode == RISING) {
|
||||
SBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
}
|
||||
else if (mode == FALLING) {
|
||||
SBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
CBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
}
|
||||
else if (mode == CHANGE) {
|
||||
SBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
SBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
}
|
||||
}
|
||||
else {
|
||||
LPC_GPIOINT->IO2IntClr = _BV(pin);
|
||||
if (mode == RISING) {
|
||||
SBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
}
|
||||
else if (mode == FALLING) {
|
||||
SBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
CBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
}
|
||||
else if (mode == CHANGE) {
|
||||
SBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
SBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin) {
|
||||
if (port == 0) {
|
||||
CBI(LPC_GPIOINT->IO0IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO0IntEnF, pin);
|
||||
LPC_GPIOINT->IO0IntClr = _BV(pin);
|
||||
}
|
||||
else {
|
||||
CBI(LPC_GPIOINT->IO2IntEnR, pin);
|
||||
CBI(LPC_GPIOINT->IO2IntEnF, pin);
|
||||
LPC_GPIOINT->IO2IntClr = _BV(pin);
|
||||
}
|
||||
}
|
||||
|
||||
extern "C" void EINT3_IRQHandler(void) {
|
||||
// Read in all current interrupt registers. We do this once as the
|
||||
// GPIO interrupt registers are on the APB bus, and this is slow.
|
||||
uint32_t rise0 = LPC_GPIOINT->IO0IntStatR,
|
||||
fall0 = LPC_GPIOINT->IO0IntStatF,
|
||||
rise2 = LPC_GPIOINT->IO2IntStatR,
|
||||
fall2 = LPC_GPIOINT->IO2IntStatF;
|
||||
|
||||
// Clear the interrupts ASAP
|
||||
LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF;
|
||||
NVIC_ClearPendingIRQ(EINT3_IRQn);
|
||||
|
||||
while (rise0 > 0) { // If multiple pins changes happened continue as long as there are interrupts pending
|
||||
const uint8_t bitloc = 31 - __CLZ(rise0); // CLZ returns number of leading zeros, 31 minus that is location of first pending interrupt
|
||||
if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
|
||||
rise0 -= _BV(bitloc);
|
||||
}
|
||||
|
||||
while (fall0 > 0) {
|
||||
const uint8_t bitloc = 31 - __CLZ(fall0);
|
||||
if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
|
||||
fall0 -= _BV(bitloc);
|
||||
}
|
||||
|
||||
while(rise2 > 0) {
|
||||
const uint8_t bitloc = 31 - __CLZ(rise2);
|
||||
if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
|
||||
rise2 -= _BV(bitloc);
|
||||
}
|
||||
|
||||
while (fall2 > 0) {
|
||||
const uint8_t bitloc = 31 - __CLZ(fall2);
|
||||
if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
|
||||
fall2 -= _BV(bitloc);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
@ -1,179 +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 "LPC1768_PWM.h"
|
||||
#include <lpc17xx_pinsel.h>
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/Delay.h"
|
||||
|
||||
// Interrupts
|
||||
void cli(void) { __disable_irq(); } // Disable
|
||||
void sei(void) { __enable_irq(); } // Enable
|
||||
|
||||
// Time functions
|
||||
void _delay_ms(const int delay_ms) {
|
||||
delay(delay_ms);
|
||||
}
|
||||
|
||||
uint32_t millis() {
|
||||
return _millis;
|
||||
}
|
||||
|
||||
// This is required for some Arduino libraries we are using
|
||||
void delayMicroseconds(uint32_t us) {
|
||||
DELAY_US(us);
|
||||
}
|
||||
|
||||
extern "C" void delay(const int msec) {
|
||||
volatile millis_t end = _millis + msec;
|
||||
SysTick->VAL = SysTick->LOAD; // reset systick counter so next systick is in exactly 1ms
|
||||
// this could extend the time between systicks by upto 1ms
|
||||
while PENDING(_millis, end) __WFE();
|
||||
}
|
||||
|
||||
// IO functions
|
||||
// As defined by Arduino INPUT(0x0), OUTPUT(0x1), INPUT_PULLUP(0x2)
|
||||
void pinMode(const pin_t pin, const uint8_t mode) {
|
||||
if (!VALID_PIN(pin)) return;
|
||||
|
||||
PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
|
||||
LPC1768_PIN_PIN(pin),
|
||||
PINSEL_FUNC_0,
|
||||
PINSEL_PINMODE_TRISTATE,
|
||||
PINSEL_PINMODE_NORMAL };
|
||||
switch (mode) {
|
||||
case INPUT:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
break;
|
||||
case OUTPUT:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
break;
|
||||
case INPUT_PULLUP:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
config.Pinmode = PINSEL_PINMODE_PULLUP;
|
||||
break;
|
||||
case INPUT_PULLDOWN:
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
config.Pinmode = PINSEL_PINMODE_PULLDOWN;
|
||||
break;
|
||||
default: return;
|
||||
}
|
||||
PINSEL_ConfigPin(&config);
|
||||
}
|
||||
|
||||
void digitalWrite(pin_t pin, uint8_t pin_status) {
|
||||
if (!VALID_PIN(pin)) return;
|
||||
|
||||
if (pin_status)
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
else
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
|
||||
pinMode(pin, OUTPUT); // Set pin mode on every write (Arduino version does this)
|
||||
|
||||
/**
|
||||
* Must be done AFTER the output state is set. Doing this before will cause a
|
||||
* 2uS glitch if writing a "1".
|
||||
*
|
||||
* When the Port Direction bit is written to a "1" the output is immediately set
|
||||
* to the value of the FIOPIN bit which is "0" because of power up defaults.
|
||||
*/
|
||||
}
|
||||
|
||||
bool digitalRead(pin_t pin) {
|
||||
if (!VALID_PIN(pin)) return false;
|
||||
|
||||
return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
|
||||
}
|
||||
|
||||
void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
if (!VALID_PIN(pin)) return;
|
||||
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
static bool out_of_PWM_slots = false;
|
||||
|
||||
uint value = MAX(MIN(pwm_value, 255), 0);
|
||||
if (value == 0 || value == 255) { // treat as digital pin
|
||||
LPC1768_PWM_detach_pin(pin); // turn off PWM
|
||||
digitalWrite(pin, value);
|
||||
}
|
||||
else {
|
||||
if (LPC1768_PWM_attach_pin(pin, 1, LPC_PWM1->MR0, 0xFF))
|
||||
LPC1768_PWM_write(pin, map(value, 0, 255, 1, LPC_PWM1->MR0)); // map 1-254 onto PWM range
|
||||
else { // out of PWM channels
|
||||
if (!out_of_PWM_slots) SERIAL_ECHOPGM(".\nWARNING - OUT OF PWM CHANNELS\n.\n"); //only warn once
|
||||
out_of_PWM_slots = true;
|
||||
digitalWrite(pin, value); // treat as a digital pin if out of channels
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
extern bool HAL_adc_finished();
|
||||
|
||||
uint16_t analogRead(pin_t adc_pin) {
|
||||
HAL_adc_start_conversion(adc_pin);
|
||||
while (!HAL_adc_finished()); // Wait for conversion to finish
|
||||
return HAL_adc_get_result();
|
||||
}
|
||||
|
||||
// **************************
|
||||
// Persistent Config Storage
|
||||
// **************************
|
||||
|
||||
void eeprom_write_byte(uint8_t *pos, unsigned char value) {
|
||||
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t * pos) { return '\0'; }
|
||||
|
||||
void eeprom_read_block(void *__dst, const void *__src, size_t __n) { }
|
||||
|
||||
void eeprom_update_block(const void *__src, void *__dst, size_t __n) { }
|
||||
|
||||
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s) {
|
||||
char format_string[20];
|
||||
snprintf(format_string, 20, "%%%d.%df", __width, __prec);
|
||||
sprintf(__s, format_string, __val);
|
||||
return __s;
|
||||
}
|
||||
|
||||
int32_t random(int32_t max) {
|
||||
return rand() % max;
|
||||
}
|
||||
|
||||
int32_t random(int32_t min, int32_t max) {
|
||||
return min + rand() % (max - min);
|
||||
}
|
||||
|
||||
void randomSeed(uint32_t value) {
|
||||
srand(value);
|
||||
}
|
||||
|
||||
int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max) {
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
@ -1,21 +0,0 @@
|
||||
Import("env")
|
||||
|
||||
env.AddPostAction(
|
||||
"$BUILD_DIR/firmware.hex",
|
||||
env.VerboseAction(" ".join([
|
||||
"sed", "-i.bak",
|
||||
"s/:10040000FFFFFFFFFFFFFFFFFFFFFFFFDEF9FFFF23/:10040000FFFFFFFFFFFFFFFFFFFFFFFFFEFFFFFFFD/",
|
||||
"$BUILD_DIR/firmware.hex"
|
||||
]), "Fixing $BUILD_DIR/firmware.hex secure flash flags"))
|
||||
env.AddPreAction(
|
||||
"upload",
|
||||
env.VerboseAction(" ".join([
|
||||
"echo",
|
||||
"'h\\nloadfile $BUILD_DIR/firmware.hex\\nr\\nq\\n'",
|
||||
">$BUILD_DIR/aux.jlink"
|
||||
]), "Creating auxiliary files"))
|
||||
|
||||
env.Replace(
|
||||
UPLOADHEXCMD=
|
||||
'JLinkExe -device MK20DX256xxx7 -speed 4000 -if swd -autoconnect 1 -CommanderScript $BUILD_DIR/aux.jlink -SkipProgOnCRCMatch = 1 -VerifyDownload = 1'
|
||||
)
|
@ -35,27 +35,23 @@
|
||||
#ifndef _FASTIO_LPC1768_H
|
||||
#define _FASTIO_LPC1768_H
|
||||
|
||||
#include <LPC17xx.h>
|
||||
#include <Arduino.h>
|
||||
#include <pinmapping.h>
|
||||
|
||||
bool useable_hardware_PWM(pin_t pin);
|
||||
#define USEABLE_HARDWARE_PWM(pin) useable_hardware_PWM(pin)
|
||||
|
||||
#define LPC_PORT_OFFSET (0x0020)
|
||||
#define LPC_PIN(pin) (1UL << pin)
|
||||
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
|
||||
#define LPC_PIN(pin) (gpio_pin(pin))
|
||||
#define LPC_GPIO(port) (gpio_port(port))
|
||||
|
||||
#define SET_DIR_INPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define SET_DIR_OUTPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define SET_DIR_INPUT(IO) (gpio_set_input(IO))
|
||||
#define SET_DIR_OUTPUT(IO) (gpio_set_output(IO))
|
||||
|
||||
#define SET_MODE(IO, mode) (pin_mode((LPC1768_PIN_PORT(IO), LPC1768_PIN_PIN(IO)), mode))
|
||||
#define SET_MODE(IO, mode) (pinMode(IO, mode))
|
||||
|
||||
#define WRITE_PIN_SET(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define WRITE_PIN_CLR(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define WRITE_PIN_SET(IO) (gpio_set(IO))
|
||||
#define WRITE_PIN_CLR(IO) (gpio_clear(IO))
|
||||
|
||||
#define READ_PIN(IO) ((LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(IO))) ? 1 : 0)
|
||||
#define WRITE_PIN(IO,V) ((V) ? WRITE_PIN_SET(IO) : WRITE_PIN_CLR(IO))
|
||||
#define READ_PIN(IO) (gpio_get(IO))
|
||||
#define WRITE_PIN(IO,V) (gpio_set(IO, V))
|
||||
|
||||
/**
|
||||
* Magic I/O routines
|
||||
@ -89,10 +85,10 @@ bool useable_hardware_PWM(pin_t pin);
|
||||
#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT)
|
||||
|
||||
/// check if pin is an input
|
||||
#define _GET_INPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR & LPC_PIN(LPC1768_PIN_PIN(IO)) != 0)
|
||||
#define _GET_INPUT(IO) (!gpio_get_dir(IO))
|
||||
|
||||
/// check if pin is an output
|
||||
#define _GET_OUTPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR & LPC_PIN(LPC1768_PIN_PIN(IO)) == 0)
|
||||
#define _GET_OUTPUT(IO) (gpio_get_dir(IO))
|
||||
|
||||
/// check if pin is a timer
|
||||
/// all gpio pins are pwm capable, either interrupt or hardware pwm controlled
|
||||
|
@ -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__
|
@ -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
|
@ -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_
|
@ -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
|
@ -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
|
@ -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
|
@ -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_
|
@ -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
|
@ -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_
|
@ -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_
|
@ -1,60 +0,0 @@
|
||||
from __future__ import print_function
|
||||
import sys
|
||||
|
||||
#dynamic build flags for generic compile options
|
||||
if __name__ == "__main__":
|
||||
args = " ".join([ "-std=gnu11",
|
||||
"-std=gnu++11",
|
||||
"-Os",
|
||||
"-mcpu=cortex-m3",
|
||||
"-mthumb",
|
||||
|
||||
"-fsigned-char",
|
||||
"-fno-move-loop-invariants",
|
||||
"-fno-strict-aliasing",
|
||||
"-fsingle-precision-constant",
|
||||
|
||||
"--specs=nano.specs",
|
||||
"--specs=nosys.specs",
|
||||
|
||||
# For external libraries
|
||||
"-IMarlin/src/HAL/HAL_LPC1768/include",
|
||||
|
||||
# For MarlinFirmware/U8glib-HAL
|
||||
"-IMarlin/src/HAL/HAL_LPC1768/u8g",
|
||||
"-DU8G_HAL_LINKS",
|
||||
|
||||
"-MMD",
|
||||
"-MP",
|
||||
"-DTARGET_LPC1768"
|
||||
])
|
||||
|
||||
for i in range(1, len(sys.argv)):
|
||||
args += " " + sys.argv[i]
|
||||
|
||||
print(args)
|
||||
|
||||
# extra script for linker options
|
||||
else:
|
||||
from SCons.Script import DefaultEnvironment
|
||||
env = DefaultEnvironment()
|
||||
env.Append(
|
||||
ARFLAGS=["rcs"],
|
||||
|
||||
ASFLAGS=["-x", "assembler-with-cpp"],
|
||||
|
||||
CXXFLAGS=[
|
||||
"-fabi-version=0",
|
||||
"-fno-use-cxa-atexit",
|
||||
"-fno-threadsafe-statics"
|
||||
],
|
||||
LINKFLAGS=[
|
||||
"-Wl,-Tframeworks/CMSIS/LPC1768/system/LPC1768.ld,--gc-sections",
|
||||
"-Os",
|
||||
"-mcpu=cortex-m3",
|
||||
"-mthumb",
|
||||
"--specs=nano.specs",
|
||||
"--specs=nosys.specs",
|
||||
"-u_printf_float"
|
||||
],
|
||||
)
|
@ -1,15 +1,6 @@
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
// ---------------------
|
||||
// Userspace entry point
|
||||
// ---------------------
|
||||
extern void setup();
|
||||
extern void loop();
|
||||
|
||||
extern "C" {
|
||||
#include <lpc17xx_gpio.h>
|
||||
}
|
||||
|
||||
#include <LPC1768_PWM.h>
|
||||
#include <usb/usb.h>
|
||||
#include <usb/usbcfg.h>
|
||||
#include <usb/usbhw.h>
|
||||
@ -17,80 +8,44 @@ extern "C" {
|
||||
#include <usb/cdc.h>
|
||||
#include <usb/cdcuser.h>
|
||||
#include <usb/mscuser.h>
|
||||
|
||||
extern "C" {
|
||||
#include <debug_frmwrk.h>
|
||||
#include <chanfs/diskio.h>
|
||||
#include <chanfs/ff.h>
|
||||
}
|
||||
#include <CDCSerial.h>
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
#include "fastio.h"
|
||||
#include "HAL_timers.h"
|
||||
#include <stdio.h>
|
||||
#include <stdarg.h>
|
||||
#include <Arduino.h>
|
||||
#include "serial.h"
|
||||
#include "LPC1768_PWM.h"
|
||||
|
||||
static __INLINE uint32_t SysTick_Config(uint32_t ticks) {
|
||||
if (ticks > SysTick_LOAD_RELOAD_Msk) return 1;
|
||||
|
||||
SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; // Set reload register
|
||||
SysTick->VAL = 0; // Load the SysTick Counter Value
|
||||
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
|
||||
SysTick_CTRL_TICKINT_Msk |
|
||||
SysTick_CTRL_ENABLE_Msk; // Enable SysTick IRQ and SysTick Timer
|
||||
|
||||
NVIC_SetPriority(SysTick_IRQn, NVIC_EncodePriority(0, 0, 0)); // Set Priority for Cortex-M3 System Interrupts
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
extern int isLPC1769();
|
||||
extern void disk_timerproc(void);
|
||||
volatile uint32_t _millis;
|
||||
|
||||
void SysTick_Handler(void) {
|
||||
++_millis;
|
||||
disk_timerproc();
|
||||
}
|
||||
|
||||
// Runs after clock init and before global static constructors
|
||||
void SystemPostInit() {
|
||||
_millis = 0; // Initialize the millisecond counter value
|
||||
SysTick_Config(SystemCoreClock / 1000); // Start millisecond global counter
|
||||
|
||||
// Runs before setup() to configure LED_PIN and used to indicate successful bootloader execution
|
||||
#if PIN_EXISTS(LED)
|
||||
SET_DIR_OUTPUT(LED_PIN);
|
||||
WRITE_PIN_CLR(LED_PIN);
|
||||
|
||||
// MKS_SBASE has 3 other LEDs the bootloader uses during flashing. Clear them.
|
||||
SET_DIR_OUTPUT(P1_19);
|
||||
WRITE_PIN_CLR(P1_19);
|
||||
SET_DIR_OUTPUT(P1_20);
|
||||
WRITE_PIN_CLR(P1_20);
|
||||
SET_DIR_OUTPUT(P1_21);
|
||||
WRITE_PIN_CLR(P1_21);
|
||||
|
||||
for (uint8_t i = 6; i--;) {
|
||||
TOGGLE(LED_PIN);
|
||||
delay(100);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
extern uint32_t MSC_SD_Init(uint8_t pdrv);
|
||||
extern "C" int isLPC1769();
|
||||
extern "C" void disk_timerproc(void);
|
||||
|
||||
int main(void) {
|
||||
void SysTick_Callback() {
|
||||
disk_timerproc();
|
||||
}
|
||||
|
||||
void HAL_init() {
|
||||
#if PIN_EXISTS(LED)
|
||||
SET_DIR_OUTPUT(LED_PIN);
|
||||
WRITE_PIN_CLR(LED_PIN);
|
||||
|
||||
// MKS_SBASE has 3 other LEDs the bootloader uses during flashing. Clear them.
|
||||
SET_DIR_OUTPUT(P1_19);
|
||||
WRITE_PIN_CLR(P1_19);
|
||||
SET_DIR_OUTPUT(P1_20);
|
||||
WRITE_PIN_CLR(P1_20);
|
||||
SET_DIR_OUTPUT(P1_21);
|
||||
WRITE_PIN_CLR(P1_21);
|
||||
|
||||
// Flash status LED 3 times to indicate Marlin has started booting
|
||||
for (uint8_t i = 0; i < 6; ++i) {
|
||||
TOGGLE(LED_PIN);
|
||||
delay(100);
|
||||
}
|
||||
#endif
|
||||
|
||||
(void)MSC_SD_Init(0);
|
||||
|
||||
USB_Init(); // USB Initialization
|
||||
USB_Connect(TRUE); // USB Connect
|
||||
USB_Init();
|
||||
USB_Connect(TRUE);
|
||||
|
||||
const uint32_t usb_timeout = millis() + 2000;
|
||||
while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
|
||||
@ -110,11 +65,7 @@ int main(void) {
|
||||
#endif
|
||||
|
||||
HAL_timer_init();
|
||||
|
||||
LPC1768_PWM_init();
|
||||
|
||||
setup();
|
||||
for (;;) loop();
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
||||
|
@ -50,35 +50,26 @@
|
||||
#ifndef SERVO_PRIVATE_H
|
||||
#define SERVO_PRIVATE_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <LPC1768_Servo.h>
|
||||
|
||||
// Macros
|
||||
//values in microseconds
|
||||
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
|
||||
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
|
||||
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
|
||||
#define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds
|
||||
class MarlinServo: public Servo {
|
||||
void move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) { // notice the pin number is zero here
|
||||
this->write(value);
|
||||
|
||||
#define MAX_SERVOS 4
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
|
||||
#define INVALID_SERVO 255 // flag indicating an invalid servo index
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
LPC1768_PWM_detach_pin(servo_info[this->servoIndex].Pin.nbr); // shut down the PWM signal
|
||||
LPC1768_PWM_attach_pin(servo_info[this->servoIndex].Pin.nbr, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH, this->servoIndex); // make sure no one else steals the slot
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Types
|
||||
|
||||
typedef struct {
|
||||
uint8_t nbr : 8 ; // a pin number from 0 to 254 (255 signals invalid pin)
|
||||
uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false
|
||||
} ServoPin_t;
|
||||
|
||||
typedef struct {
|
||||
ServoPin_t Pin;
|
||||
unsigned int pulse_width; // pulse width in microseconds
|
||||
} ServoInfo_t;
|
||||
|
||||
// Global variables
|
||||
|
||||
extern uint8_t ServoCount;
|
||||
extern ServoInfo_t servo_info[MAX_SERVOS];
|
||||
#define HAL_SERVO_LIB MarlinServo
|
||||
|
||||
#endif // SERVO_PRIVATE_H
|
||||
|
@ -55,7 +55,7 @@
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
@ -77,7 +77,7 @@
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
@ -55,13 +55,13 @@
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
||||
//#include <inttypes.h>
|
||||
#include <U8glib.h>
|
||||
#include "../shared/Delay.h"
|
||||
#include "../../shared/Delay.h"
|
||||
|
||||
#define SPI_FULL_SPEED 0
|
||||
#define SPI_HALF_SPEED 1
|
@ -55,13 +55,13 @@
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
||||
#include <U8glib.h>
|
||||
#include "SoftwareSPI.h"
|
||||
#include "../shared/Delay.h"
|
||||
#include "../../shared/Delay.h"
|
||||
|
||||
#define SPI_SPEED 3 // About 1 MHz
|
||||
|
@ -55,7 +55,7 @@
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(DOGLCD)
|
||||
|
13
Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp
Normal file
13
Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp
Normal file
@ -0,0 +1,13 @@
|
||||
#ifdef TARGET_LPC1768
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../../feature/emergency_parser.h"
|
||||
EmergencyParser::State emergency_state;
|
||||
bool CDC_RecvCallback(const char buffer) {
|
||||
emergency_parser.update(emergency_state, buffer);
|
||||
return true;
|
||||
}
|
||||
#endif // ENABLED(EMERGENCY_PARSER)
|
||||
|
||||
#endif // TARGET_LPC1768
|
@ -0,0 +1,36 @@
|
||||
[Version]
|
||||
Signature="$Windows NT$"
|
||||
Class=Ports
|
||||
ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
|
||||
Provider=%PROVIDER%
|
||||
DriverVer =04/14/2008, 5.1.2600.5512
|
||||
|
||||
[Manufacturer]
|
||||
%PROVIDER%=DeviceList,ntamd64
|
||||
|
||||
|
||||
[DeviceList]
|
||||
%DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00
|
||||
|
||||
[DeviceList.ntamd64]
|
||||
%DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00
|
||||
|
||||
|
||||
[LPC1768USB]
|
||||
include=mdmcpq.inf
|
||||
CopyFiles=FakeModemCopyFileSection
|
||||
AddReg=LowerFilterAddReg,SerialPropPageAddReg
|
||||
|
||||
[LPC1768USB.Services]
|
||||
include=mdmcpq.inf
|
||||
AddService=usbser, 0x00000002, LowerFilter_Service_Inst
|
||||
|
||||
[SerialPropPageAddReg]
|
||||
HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
|
||||
|
||||
|
||||
[Strings]
|
||||
PROVIDER = "marlinfw.org"
|
||||
DRIVER.SVC = "Marlin USB Driver"
|
||||
DESCRIPTION= "Marlin USB Serial"
|
||||
COMPOSITE = "Marlin USB VCOM"
|
@ -73,7 +73,7 @@
|
||||
#elif IS_TEENSY35 || IS_TEENSY36
|
||||
#include "../HAL_TEENSY35_36/HAL_Servo_Teensy.h"
|
||||
#elif defined(TARGET_LPC1768)
|
||||
#include "../HAL_LPC1768/LPC1768_Servo.h"
|
||||
#include "../HAL_LPC1768/servo_private.h"
|
||||
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
|
||||
#include "../HAL_STM32F1/HAL_Servo_STM32F1.h"
|
||||
#elif defined(STM32GENERIC) && defined(STM32F4)
|
||||
|
Reference in New Issue
Block a user