diff --git a/Marlin/pins_RAMPS.h b/Marlin/pins_RAMPS.h
index f3e268cdec95..d7185d9b7511 100644
--- a/Marlin/pins_RAMPS.h
+++ b/Marlin/pins_RAMPS.h
@@ -44,7 +44,7 @@
* 7 | 11
*/
-#if !defined(IS_RAMPS_SMART) && !defined(IS_RAMPS_DUO) && !defined(IS_RAMPS4DUE)
+#if !defined(IS_RAMPS_SMART) && !defined(IS_RAMPS_DUO) && !defined(IS_RAMPS4DUE) && !defined(TARGET_LPC1768)
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
#error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu."
#endif
@@ -208,6 +208,15 @@
#define PS_ON_PIN 12
+#if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN)
+ #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first
+ #define CASE_LIGHT_PIN 6 // MUST BE HARDWARE PWM
+ #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \
+ && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD))) // try to use AUX 2
+ #define CASE_LIGHT_PIN 44 // MUST BE HARDWARE PWM
+ #endif
+#endif
+
//
// LCD / Controller
//
@@ -271,10 +280,10 @@
#define SD_DETECT_PIN -1
#define KILL_PIN 41
#elif ENABLED(LCD_I2C_VIKI)
- #define BTN_EN1 22 // reverse if the encoder turns the wrong way.
- #define BTN_EN2 7 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf
- // tells about 40/42.
- // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13.
+
+ #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42.
+ #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13.
+
#define BTN_ENC -1
#define LCD_SDSS 53
#define SD_DETECT_PIN 49
diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h
index 5d076ac5682d..fd9cbbff2054 100644
--- a/Marlin/src/HAL/HAL.h
+++ b/Marlin/src/HAL/HAL.h
@@ -87,6 +87,10 @@ void spiSendBlock(uint8_t token, const uint8_t* buf);
#define CPU_32_BIT
#include "HAL_TEENSY35_36/HAL_Teensy.h"
#include "math_32bit.h"
+#elif defined(TARGET_LPC1768)
+ #define CPU_32_BIT
+ #include "math_32bit.h"
+ #include "HAL_LPC1768/HAL.h"
#else
#error Unsupported Platform!
#endif
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL.cpp b/Marlin/src/HAL/HAL_LPC1768/HAL.cpp
new file mode 100644
index 000000000000..79d41c3c343d
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL.cpp
@@ -0,0 +1,177 @@
+/* **************************************************************************
+
+ Marlin 3D Printer Firmware
+ Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+
+ 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 .
+****************************************************************************/
+
+
+/**
+ *
+ * For TARGET_LPC1768
+ */
+
+#ifdef TARGET_LPC1768
+
+#include "../HAL.h"
+
+HalSerial usb_serial(USBTX, USBRX);
+Timer system_counter;
+
+//u8glib required fucntions
+extern "C" void u8g_xMicroDelay(uint16_t val) {
+ delayMicroseconds(val);
+}
+extern "C" void u8g_MicroDelay(void) {
+ u8g_xMicroDelay(1);
+}
+extern "C" void u8g_10MicroDelay(void) {
+ u8g_xMicroDelay(10);
+}
+extern "C" void u8g_Delay(uint16_t val) {
+ u8g_xMicroDelay(val*1000);
+}
+//************************//
+
+int availableMemory(int resolution = 16, int maximum = 0x4000, bool disableInterrupts = false) {
+ if (resolution < 1) resolution = 1;
+ if (maximum < 0) maximum = 0;
+
+ int low = 0;
+ int high = maximum + 1;
+
+ if (disableInterrupts) __disable_irq();
+ while (high - low > resolution) {
+ int mid = (low + high) / 2;
+ void* p = malloc(mid);
+ if (p == NULL) {
+ high = mid;
+ } else {
+ free(p);
+ low = mid;
+ }
+ }
+ if (disableInterrupts) __enable_irq();
+ return low;
+}
+
+// return free memory between end of heap (or end bss) and whatever is current
+int freeMemory(){
+ return availableMemory();
+}
+
+
+// --------------------------------------------------------------------------
+// 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);
+ LPC_ADC->ADCR = (0 << 0) // SEL: 0 = no channels selected
+ | (8 << 8) // CLKDIV: PCLK max ~= 25MHz, /25 to give safe 1MHz at fastest
+ | (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
+}
+
+void HAL_adc_enable_channel(int pin) {
+ LPC_PINCON->PINSEL1 &= ~0x000FC000;
+ LPC_PINCON->PINSEL1 |= 0x00054000;
+ //LPC_PINCON->PINSEL3 |= 0xC0000000;
+}
+
+void HAL_adc_start_conversion(uint8_t adc_pin) {
+ if(adc_pin_map[adc_pin].port == 0xFF) {
+ MYSERIAL.serial_port.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\r\n",adc_pin);
+ return;
+ }
+ LPC_ADC->ADCR &= ~0xFF; // Reset
+ LPC_ADC->ADCR |= ( 0x01 << adc_pin_map[adc_pin].adc ); // Select Channel
+ LPC_ADC->ADCR |= ( 0x01 << 24 ); // start conversion
+}
+
+uint16_t HAL_adc_get_result(void) {
+ uint32_t data = LPC_ADC->ADGDR;
+ LPC_ADC->ADCR &= ~(1 << 24); //stop conversion
+ if ( data & ADC_OVERRUN ) return 0;
+ return ((data >> 6) & 0x3ff); //10bit
+}
+
+// ---------------------
+// Userspace entry point
+// ---------------------
+extern void setup();
+extern void loop();
+
+void pinMode(int pin, int mode);
+void digitalWrite(int pin, int pin_status);
+bool digitalRead(int pin);
+
+extern "C" void SysTick_Handler(void) {
+ _millis++;
+}
+
+#define SBIT_CNTEN 0
+#define SBIT_PWMEN 2
+#define SBIT_PWMMR0R 1
+
+#define PWM_1 0 //P2_0 (0-1 Bits of PINSEL4)
+#define PWM_2 2 //P2_1 (2-3 Bits of PINSEL4)
+#define PWM_3 4 //P2_2 (4-5 Bits of PINSEL4)
+#define PWM_4 6 //P2_3 (6-7 Bits of PINSEL4)
+#define PWM_5 8 //P2_4 (8-9 Bits of PINSEL4)
+#define PWM_6 10 //P2_5 (10-11 Bits of PINSEL4)
+
+void HAL_pwm_init(void) {
+ LPC_PINCON->PINSEL4 = (1<TCR = (1<PR = 0x0; // No prescalar
+ LPC_PWM1->MCR = (1<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 = (1<<0) | (1<<5) | (1<<6);
+ // Enable the PWM output pins for PWM_5-PWM_6(P2_4 - P2_5)
+ LPC_PWM1->PCR = (1<<13) | (1<<14);
+}
+
+extern "C" int main() {
+ SysTick_Config(SystemCoreClock / 1000);
+ // Enable GPIO clock
+ LPC_SC->PCONP |= (1 << 15);
+
+ HAL_timer_init();
+ //HAL_pwm_init();
+
+ system_counter.start(); //todo: rethink micros?
+ setup();
+
+ while (true) {
+ loop();
+ }
+}
+
+#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL.h b/Marlin/src/HAL/HAL_LPC1768/HAL.h
new file mode 100644
index 000000000000..9b7e37a6552c
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL.h
@@ -0,0 +1,102 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+ *
+ * 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 .
+ *
+ */
+
+/**
+ * Description: HAL for Arduino Due and compatible (SAM3X8E)
+ *
+ * For ARDUINO_ARCH_SAM
+ */
+
+#ifndef _HAL_LPC1768_H
+#define _HAL_LPC1768_H
+
+// --------------------------------------------------------------------------
+// Includes
+// --------------------------------------------------------------------------
+
+#include
+#include
+
+#define RETARGET_H // todo: this "disables" a conflicting header in mbed local filesystem implementation
+#include
+#undef PACKED
+
+extern Timer system_counter;
+extern uint32_t _millis;
+
+#define USBCON
+
+//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 "fastio.h"
+#include "watchdog.h"
+#include "serial.h"
+#include "HAL_timers.h"
+
+
+//todo: why so much higher than arduino? 96Mhz, 20cycle low (208ns), 25 cycle data(260ns), 25cycle high(260ns)
+#define ST7920_DELAY_1 DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP
+#define ST7920_DELAY_2 DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP
+#define ST7920_DELAY_3 DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP;DELAY_5_NOP
+
+//Serial override
+extern HalSerial usb_serial;
+#define MYSERIAL usb_serial
+
+#ifndef analogInputToDigitalPin
+ #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
+#endif
+
+#define CRITICAL_SECTION_START uint32_t primask=__get_PRIMASK(); __disable_irq();
+#define CRITICAL_SECTION_END if (primask==0) __enable_irq();
+
+//Utility functions
+int freeMemory(void);
+
+// SPI: Extended functions which take a channel number (hardware SPI only)
+/** Write single byte to specified SPI channel */
+void spiSend(uint32_t chan, byte b);
+/** Write buffer to specified SPI channel */
+void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
+/** Read single byte from specified SPI channel */
+uint8_t spiRec(uint32_t chan);
+
+// ADC
+#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()
+
+void HAL_adc_init(void);
+void HAL_adc_enable_channel(int pin);
+void HAL_adc_start_conversion (uint8_t adc_pin);
+uint16_t HAL_adc_get_result(void);
+
+#endif // _HAL_LPC1768_H
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp b/Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp
new file mode 100644
index 000000000000..55e5d659385b
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp
@@ -0,0 +1,177 @@
+/**
+ * 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 .
+ *
+ */
+
+/**
+ * Software SPI functions originally from Arduino Sd2Card Library
+ * Copyright (C) 2009 by William Greiman
+ */
+
+/**
+ *
+ * For TARGET_LPC1768
+ */
+
+#ifdef TARGET_LPC1768
+
+// --------------------------------------------------------------------------
+// Includes
+// --------------------------------------------------------------------------
+
+#include "../../../MarlinConfig.h"
+
+// --------------------------------------------------------------------------
+// Public Variables
+// --------------------------------------------------------------------------
+
+
+// --------------------------------------------------------------------------
+// Public functions
+// --------------------------------------------------------------------------
+
+#if ENABLED(SOFTWARE_SPI)
+ // --------------------------------------------------------------------------
+ // software SPI
+ // --------------------------------------------------------------------------
+ // bitbanging transfer
+ // run at ~100KHz (necessary for init)
+ static uint8_t spiTransfer(uint8_t b) { // using Mode 0
+ for (int bits = 0; bits < 8; bits++) {
+ if (b & 0x80) {
+ WRITE(MOSI_PIN, HIGH);
+ }
+ else {
+ WRITE(MOSI_PIN, LOW);
+ }
+ b <<= 1;
+
+ WRITE(SCK_PIN, HIGH);
+ delayMicroseconds(3U);
+
+ if (READ(MISO_PIN)) {
+ b |= 1;
+ }
+ WRITE(SCK_PIN, LOW);
+ delayMicroseconds(3U);
+ }
+ return b;
+ }
+
+ void spiBegin() {
+ SET_OUTPUT(SS_PIN);
+ WRITE(SS_PIN, HIGH);
+ SET_OUTPUT(SCK_PIN);
+ SET_INPUT(MISO_PIN);
+ SET_OUTPUT(MOSI_PIN);
+ }
+
+ void spiInit(uint8_t spiRate) {
+ UNUSED(spiRate);
+ WRITE(SS_PIN, HIGH);
+ WRITE(MOSI_PIN, HIGH);
+ WRITE(SCK_PIN, LOW);
+ }
+
+ uint8_t spiRec() {
+ WRITE(SS_PIN, LOW);
+ uint8_t b = spiTransfer(0xff);
+ WRITE(SS_PIN, HIGH);
+ return b;
+ }
+
+ void spiRead(uint8_t*buf, uint16_t nbyte) {
+ if (nbyte == 0) return;
+ WRITE(SS_PIN, LOW);
+ for (int i = 0; i < nbyte; i++) {
+ buf[i] = spiTransfer(0xff);
+ }
+ WRITE(SS_PIN, HIGH);
+ }
+
+ void spiSend(uint8_t b) {
+ WRITE(SS_PIN, LOW);
+ uint8_t response = spiTransfer(b);
+ UNUSED(response);
+ WRITE(SS_PIN, HIGH);
+ }
+
+ static void spiSend(const uint8_t* buf, size_t n) {
+ uint8_t response;
+ if (n == 0) return;
+ WRITE(SS_PIN, LOW);
+ for (uint16_t i = 0; i < n; i++) {
+ response = spiTransfer(buf[i]);
+ }
+ UNUSED(response);
+ WRITE(SS_PIN, HIGH);
+ }
+
+ void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ uint8_t response;
+
+ WRITE(SS_PIN, LOW);
+ response = spiTransfer(token);
+
+ for (uint16_t i = 0; i < 512; i++) {
+ response = spiTransfer(buf[i]);
+ }
+ UNUSED(response);
+ WRITE(SS_PIN, HIGH);
+ }
+#else
+ void spiBegin() {
+ }
+
+ void spiInit(uint8_t spiRate) {
+ }
+
+ void spiSend(byte b) {
+ }
+
+ void spiSend(const uint8_t* buf, size_t n) {
+ }
+
+ void spiSend(uint32_t chan, byte b) {
+ }
+
+ void spiSend(uint32_t chan, const uint8_t* buf, size_t n) {
+
+ }
+
+ // Read single byte from SPI
+ uint8_t spiRec() {
+ return 0;
+ }
+
+ uint8_t spiRec(uint32_t chan) {
+ return 0;
+ }
+
+ // Read from SPI into buffer
+ void spiRead(uint8_t*buf, uint16_t nbyte) {
+ }
+
+ // Write from buffer to SPI
+ void spiSendBlock(uint8_t token, const uint8_t* buf) {
+ }
+#endif // ENABLED(SOFTWARE_SPI)
+
+#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL_timers.cpp b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.cpp
new file mode 100644
index 000000000000..d934f536af8e
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.cpp
@@ -0,0 +1,93 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
+ *
+ * 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 .
+ *
+ */
+
+/**
+ * Description:
+ *
+ * For TARGET_LPC1768
+ */
+
+#ifdef TARGET_LPC1768
+
+#include "../HAL.h"
+#include "HAL_timers.h"
+
+void HAL_timer_init (void) {
+ LPC_SC->PCONP |= (0x1 << 0x1); // power on timer0
+ LPC_TIM0->PR = ((HAL_TIMER_RATE / HAL_STEPPER_TIMER_RATE) - 1); // Use prescaler to set frequency if needed
+
+ LPC_SC->PCONP |= (0x1 << 0x2); // power on timer1
+ LPC_TIM1->PR = ((HAL_TIMER_RATE / 1000000) - 1);
+}
+
+void HAL_timer_start (uint8_t timer_num, uint32_t frequency) {
+ switch(timer_num) {
+ case 0:
+ LPC_TIM0->MCR = 3; // Match on MR0, reset on MR0
+ LPC_TIM0->MR0 = (uint32_t)(HAL_STEPPER_TIMER_RATE / frequency); // Match value (period) to set frequency
+ LPC_TIM0->TCR = (1 << 0); // enable
+ break;
+ case 1:
+ LPC_TIM1->MCR = 3;
+ LPC_TIM1->MR0 = (uint32_t)(HAL_TEMP_TIMER_RATE / frequency);;
+ LPC_TIM1->TCR = (1 << 0);
+ break;
+ default:
+ return;
+ }
+}
+
+void HAL_timer_enable_interrupt (uint8_t timer_num) {
+ switch(timer_num) {
+ case 0:
+ NVIC_EnableIRQ(TIMER0_IRQn); // Enable interrupt handler
+ break;
+ case 1:
+ NVIC_EnableIRQ(TIMER1_IRQn);
+ break;
+ }
+}
+
+void HAL_timer_disable_interrupt (uint8_t timer_num) {
+ switch(timer_num) {
+ case 0:
+ NVIC_DisableIRQ(TIMER0_IRQn); // disable interrupt handler
+ break;
+ case 1:
+ NVIC_DisableIRQ(TIMER1_IRQn);
+ break;
+ }
+}
+
+void HAL_timer_isr_prologue (uint8_t timer_num) {
+ switch(timer_num) {
+ case 0:
+ LPC_TIM0->IR |= 1; //Clear the Interrupt
+ break;
+ case 1:
+ LPC_TIM1->IR |= 1;
+ break;
+ }
+}
+
+
+#endif // TARGET_LPC1768
diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h
new file mode 100644
index 000000000000..5c1db068da31
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h
@@ -0,0 +1,122 @@
+/**
+ * Marlin 3D Printer Firmware
+ *
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
+ *
+ * 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 .
+ *
+ */
+
+/**
+ * HAL for Arduino Due and compatible (SAM3X8E)
+ *
+ * For ARDUINO_ARCH_SAM
+ */
+
+#ifndef _HAL_TIMERS_H
+#define _HAL_TIMERS_H
+
+// --------------------------------------------------------------------------
+// Includes
+// --------------------------------------------------------------------------
+
+#include
+
+// --------------------------------------------------------------------------
+// Defines
+// --------------------------------------------------------------------------
+
+#define FORCE_INLINE __attribute__((always_inline)) inline
+
+#define HAL_TIMER_TYPE uint32_t
+#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
+
+#define STEP_TIMER_NUM 0 // index of timer to use for stepper
+#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
+
+#define F_CPU 96000000
+#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals
+#define STEPPER_TIMER_PRESCALE 1.0 // prescaler for setting stepper frequency
+#define HAL_STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
+#define HAL_TICKS_PER_US ((HAL_STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per us
+#define HAL_TEMP_TIMER_RATE 1000000
+#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
+
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt (STEP_TIMER_NUM)
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt (STEP_TIMER_NUM)
+
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt (TEMP_TIMER_NUM)
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt (TEMP_TIMER_NUM)
+
+#define HAL_ENABLE_ISRs() do { if (thermalManager.in_temp_isr)DISABLE_TEMPERATURE_INTERRUPT(); else ENABLE_TEMPERATURE_INTERRUPT(); ENABLE_STEPPER_DRIVER_INTERRUPT(); } while(0)
+//
+#define HAL_STEP_TIMER_ISR extern "C" void TIMER0_IRQHandler(void)
+#define HAL_TEMP_TIMER_ISR extern "C" void TIMER1_IRQHandler(void)
+
+// --------------------------------------------------------------------------
+// Types
+// --------------------------------------------------------------------------
+
+// --------------------------------------------------------------------------
+// Public Variables
+// --------------------------------------------------------------------------
+
+// --------------------------------------------------------------------------
+// Public functions
+// --------------------------------------------------------------------------
+void HAL_timer_init (void);
+void HAL_timer_start (uint8_t timer_num, uint32_t frequency);
+
+static FORCE_INLINE void HAL_timer_set_count (uint8_t timer_num, HAL_TIMER_TYPE count) {
+ switch(timer_num) {
+ case 0:
+ LPC_TIM0->MR0 = count;
+ break;
+ case 1:
+ LPC_TIM1->MR0 = count;
+ break;
+ default:
+ return;
+ }
+}
+
+static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
+ switch(timer_num) {
+ case 0:
+ return LPC_TIM0->MR0;
+ case 1:
+ return LPC_TIM1->MR0;
+ default:
+ return 0;
+ }
+}
+
+static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(uint8_t timer_num) {
+ switch(timer_num) {
+ case 0:
+ return LPC_TIM0->TC;
+ case 1:
+ return LPC_TIM1->TC;
+ default:
+ return 0;
+ }
+}
+
+void HAL_timer_enable_interrupt(uint8_t timer_num);
+void HAL_timer_disable_interrupt(uint8_t timer_num);
+void HAL_timer_isr_prologue (uint8_t timer_num);
+
+
+#endif // _HAL_TIMERS_DUE_H
diff --git a/Marlin/src/HAL/HAL_LPC1768/Servo.cpp b/Marlin/src/HAL/HAL_LPC1768/Servo.cpp
new file mode 100644
index 000000000000..94cd7748342c
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/Servo.cpp
@@ -0,0 +1,44 @@
+/**
+ * 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 .
+ *
+ */
+
+/*
+ Copyright (c) 2013 Arduino LLC. 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
+
+
+#endif // ARDUINO_ARCH_SAM
diff --git a/Marlin/src/HAL/HAL_LPC1768/arduino.cpp b/Marlin/src/HAL/HAL_LPC1768/arduino.cpp
new file mode 100644
index 000000000000..888a23655944
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/arduino.cpp
@@ -0,0 +1,140 @@
+/**
+ * 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 .
+ *
+ */
+
+#ifdef TARGET_LPC1768
+
+#include "HAL.h"
+
+// Interrupts
+void cli(void) { __disable_irq(); } // Disable
+void sei(void) { __enable_irq(); } // Enable
+
+// Program Memory
+void serialprintPGM(const char * str){
+ usb_serial.print(str);
+}
+
+// Time functions
+void _delay_ms(int delay_ms) {
+ delay (delay_ms);
+}
+
+uint32_t _millis = 0;
+uint32_t millis() {
+ return _millis;
+}
+
+uint64_t micros() {
+ return system_counter.read_us();
+}
+
+void delayMicroseconds(uint32_t us) {
+ wait_us(us);
+}
+
+void delay(int milis) {
+ wait_ms(milis);
+}
+
+// IO functions
+// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
+void pinMode(int pin, int mode) {
+ if(pin_map[pin].port == 0xFF) {
+ MYSERIAL.serial_port.printf("HAL: pinMode: no pinmap for %d\r\n", pin);
+ return;
+ }
+
+ switch(mode) {
+ case INPUT:
+ LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
+ pin_mode(LPC_MBED_PIN(pin_map[pin].port, pin_map[pin].pin), PinMode::PullNone);
+ break;
+ case OUTPUT:
+ LPC_GPIO(pin_map[pin].port)->FIODIR |= LPC_PIN(pin_map[pin].pin);
+ pin_mode(LPC_MBED_PIN(pin_map[pin].port, pin_map[pin].pin), PinMode::PullNone);
+ break;
+ case INPUT_PULLUP:
+ LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
+ pin_mode(LPC_MBED_PIN(pin_map[pin].port, pin_map[pin].pin), PinMode::PullUp);
+ break;
+ default:
+ MYSERIAL.serial_port.printf("HAL: pinMode: Invalid Mode(%d)\r\n", mode);
+ }
+}
+
+void digitalWrite(int pin, int pin_status) {
+ if(pin_map[pin].port == 0xFF) {
+ MYSERIAL.serial_port.printf("HAL: digitalWrite: no pinmap for %d\r\n", pin);
+ return;
+ }
+ if(pin_status) {
+ LPC_GPIO(pin_map[pin].port)->FIOSET = LPC_PIN(pin_map[pin].pin);
+ } else {
+ LPC_GPIO(pin_map[pin].port)->FIOCLR = LPC_PIN(pin_map[pin].pin);
+ }
+}
+
+bool digitalRead(int pin) {
+ if(pin_map[pin].port == 0xFF) {
+ MYSERIAL.serial_port.printf("HAL: digitalRead: no pinmap for %d\r\n", pin);
+ return false;
+ }
+ return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
+}
+
+void analogWrite(int pin, int pin_status) { //todo: Hardware PWM
+/*
+ if(pin == P2_4) {
+ LPC_PWM1->MR5 = pin_status; //set value
+ LPC_PWM1->LER = (1<<5); //set latch
+ } else if(pin == P2_5) {
+ LPC_PWM1->MR6 = pin_status;
+ LPC_PWM1->LER = (1<<6);
+ }*/
+}
+
+uint16_t analogRead(int adc_pin) {
+ HAL_adc_start_conversion (adc_pin);
+ return HAL_adc_get_result();
+}
+
+// **************************
+// Persistent Config Storage
+// **************************
+
+void eeprom_write_byte(unsigned char *pos, char value) {
+
+}
+
+unsigned char 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) {
+
+}
+
+#endif //TARGET_LPC1768
diff --git a/Marlin/src/HAL/HAL_LPC1768/arduino.h b/Marlin/src/HAL/HAL_LPC1768/arduino.h
new file mode 100644
index 000000000000..a48821da0266
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/arduino.h
@@ -0,0 +1,89 @@
+/**
+ * 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 .
+ *
+ */
+
+#ifndef __ARDUINO_H__
+#define __ARDUINO_H__
+
+#include
+
+#define LOW 0x00
+#define HIGH 0x01
+
+#define INPUT 0x00
+#define OUTPUT 0x01
+#define INPUT_PULLUP 0x02
+
+#define _BV(bit) (1 << (bit))
+
+typedef uint8_t byte;
+#define PROGMEM
+#define PSTR(v) (v)
+#define PGM_P const char *
+#define max(v1, v2) std::max((int)v1,(int)v2)
+#define min(v1, v2) std::min((int)v1,(int)v2)
+#define abs(v) std::abs(v)
+#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
+
+// Program Memory
+#define pgm_read_ptr(address_short) (*(address_short))
+#define pgm_read_byte_near(address_short) (*address_short)
+#define pgm_read_byte(address_short) pgm_read_byte_near(address_short)
+#define pgm_read_float_near(address_short) (*address_short)
+#define pgm_read_float(address_short) pgm_read_float_near(address_short)
+#define pgm_read_word_near(address_short) (*address_short)
+#define pgm_read_word(address_short) pgm_read_word_near(address_short)
+#define pgm_read_dword_near(address_short) (*address_short)
+#define pgm_read_dword(address_short) pgm_read_dword_near(address_short)
+
+#define sprintf_P sprintf
+#define strstr_P strstr
+#define strncpy_P strncpy
+#define vsnprintf_P vsnprintf
+void serialprintPGM(const char *);
+
+// Time functions
+void delay(int milis);
+void _delay_ms(int delay);
+void delayMicroseconds(unsigned long);
+uint32_t millis();
+uint64_t micros();
+
+//IO functions
+void pinMode(int pin_number, int mode);
+void digitalWrite(int pin_number, int pin_status);
+bool digitalRead(int pin);
+void analogWrite(int pin_number, int pin_status);
+uint16_t analogRead(int adc_pin);
+
+// EEPROM
+void eeprom_write_byte(unsigned char *pos, unsigned char value);
+unsigned char eeprom_read_byte(unsigned char *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);
+
+#endif // __ARDUINO_DEF_H__
diff --git a/Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h b/Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h
new file mode 100644
index 000000000000..1bb8586a28ba
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h
@@ -0,0 +1,70 @@
+/**
+ * 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 .
+ *
+ */
+
+/**
+ * Endstop Interrupts
+ *
+ * Without endstop interrupts the endstop pins must be polled continually in
+ * the stepper-ISR via endstops.update(), most of the time finding no change.
+ * With this feature endstops.update() is called only when we know that at
+ * least one endstop has changed state, saving valuable CPU cycles.
+ *
+ * This feature only works when all used endstop pins can generate an 'external interrupt'.
+ *
+ * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
+ * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
+ */
+
+ #ifndef _ENDSTOP_INTERRUPTS_H_
+ #define _ENDSTOP_INTERRUPTS_H_
+
+void setup_endstop_interrupts(void) {
+ #if HAS_X_MAX
+ attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
+ #endif
+ #if HAS_X_MIN
+ attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
+ #endif
+ #if HAS_Y_MAX
+ attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
+ #endif
+ #if HAS_Y_MIN
+ attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
+ #endif
+ #if HAS_Z_MAX
+ attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
+ #endif
+ #if HAS_Z_MIN
+ attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
+ #endif
+ #if HAS_Z2_MAX
+ attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
+ #endif
+ #if HAS_Z2_MIN
+ attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
+ #endif
+ #if HAS_Z_MIN_PROBE_PIN
+ attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
+ #endif
+}
+
+#endif //_ENDSTOP_INTERRUPTS_H_
diff --git a/Marlin/src/HAL/HAL_LPC1768/fastio.h b/Marlin/src/HAL/HAL_LPC1768/fastio.h
new file mode 100644
index 000000000000..a3e35854e4a6
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/fastio.h
@@ -0,0 +1,118 @@
+/**
+ * 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 .
+ *
+ */
+
+/**
+ This code contributed by Triffid_Hunter and modified by Kliment
+ why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
+*/
+
+/**
+ * Description: Fast IO functions LPC1768
+ *
+ * For TARGET LPC1768
+ */
+
+#ifndef _FASTIO_LPC1768_H
+#define _FASTIO_LPC1768_H
+
+#include
+
+#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_MBED_PIN(port, pin) (PinName(LPC_GPIO0_BASE + (port*32) + pin))
+
+#define SET_DIR_INPUT(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR &= ~LPC_PIN(DIO ## IO ##_PIN))
+#define SET_DIR_OUTPUT(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR |= LPC_PIN(DIO ## IO ##_PIN))
+
+#define SET_MODE(IO, mbed_mode) (pin_mode(LPC_MBED_PIN(DIO ## IO ## _PORT, DIO ## IO ## _PIN), mbed_mode))
+
+#define WRITE_PIN_SET(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIOSET = LPC_PIN(DIO ## IO ##_PIN))
+#define WRITE_PIN_CLR(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIOCLR = LPC_PIN(DIO ## IO ##_PIN))
+
+#define READ_PIN(IO) ((LPC_GPIO(DIO ## IO ## _PORT)->FIOPIN & LPC_PIN(DIO ## IO ##_PIN)) ? 1 : 0)
+#define WRITE_PIN(IO, v) ((v) ? WRITE_PIN_SET(IO) : WRITE_PIN_CLR(IO))
+
+/**
+ magic I/O routines
+ now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0);
+*/
+
+/// Read a pin
+#define _READ(IO) READ_PIN(IO)
+
+/// Write to a pin
+#define _WRITE_VAR(IO, v) digitalWrite(IO, v)
+
+#define _WRITE(IO, v) WRITE_PIN(IO, v)
+
+/// toggle a pin
+#define _TOGGLE(IO) _WRITE(IO, !READ(IO))
+
+/// set pin as input
+#define _SET_INPUT(IO) SET_DIR_INPUT(IO)
+
+/// set pin as output
+#define _SET_OUTPUT(IO) SET_DIR_OUTPUT(IO)
+
+/// set pin as input with pullup mode
+#define _PULLUP(IO, v) SET_MODE(IO, PinMode::PullUp)
+
+/// check if pin is an input
+#define _GET_INPUT(IO)
+/// check if pin is an output
+#define _GET_OUTPUT(IO)
+
+/// check if pin is an timer
+#define _GET_TIMER(IO)
+
+// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
+
+/// Read a pin wrapper
+#define READ(IO) _READ(IO)
+
+/// Write to a pin wrapper
+#define WRITE_VAR(IO, v) _WRITE_VAR(IO, v)
+#define WRITE(IO, v) _WRITE(IO, v)
+
+/// toggle a pin wrapper
+#define TOGGLE(IO) _TOGGLE(IO)
+
+/// set pin as input wrapper
+#define SET_INPUT(IO) _SET_INPUT(IO)
+/// set pin as input with pullup wrapper
+#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
+/// set pin as output wrapper
+#define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); _WRITE(IO, LOW); }while(0)
+
+/// check if pin is an input wrapper
+#define GET_INPUT(IO) _GET_INPUT(IO) // todo: Never used?
+/// check if pin is an output wrapper
+#define GET_OUTPUT(IO) _GET_OUTPUT(IO) //todo: Never Used?
+
+/// check if pin is an timer wrapper
+#define GET_TIMER(IO) _GET_TIMER(IO)
+
+// Shorthand
+#define OUT_WRITE(IO, v) { SET_OUTPUT(IO); WRITE(IO, v); }
+
+#endif /* _FASTIO_LPC1768_H */
diff --git a/Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h b/Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h
new file mode 100644
index 000000000000..bd758aa223c7
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/pinmap_re_arm.h
@@ -0,0 +1,247 @@
+/**
+ * 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 .
+ *
+ */
+
+#ifndef __PINMAP_RE_ARM_H__
+#define __PINMAP_RE_ARM_H__
+
+// ******************
+// Runtime pinmapping
+// ******************
+
+const adc_pin_data adc_pin_map[] = {
+ {0xFF, 0xFF, 0xFF}, //A0
+ {0xFF, 0xFF, 0xFF}, //A1
+ {0xFF, 0xFF, 0xFF}, //A2
+ {0xFF, 0xFF, 0xFF}, //A3
+ {0xFF, 0xFF, 0xFF}, //A4
+ {0xFF, 0xFF, 0xFF}, //A5
+ {0xFF, 0xFF, 0xFF}, //A6
+ {0xFF, 0xFF, 0xFF}, //A7
+ {0xFF, 0xFF, 0xFF}, //A8
+ {0xFF, 0xFF, 0xFF}, //A9
+ {0xFF, 0xFF, 0xFF}, //A10
+ {0xFF, 0xFF, 0xFF}, //A11
+ {0xFF, 0xFF, 0xFF}, //A12
+ {0, 23, 0}, //A13 - TEMP_0_PIN
+ {0, 24, 1}, //A14 - TEMP_BED_PIN
+ {0, 25, 2} //A15 - TEMP_1_PIN
+};
+
+const pin_data pin_map[] = { // pin map for variable pin function
+ {0, 2}, //DIO0 - TXD0
+ {0, 3}, //DIO1 - RXD0
+ {1, 25}, //DIO2 - X_MAX_PIN
+ {1, 24}, //DIO3 - X_MIN_PIN
+ {0xFF,0xFF}, //DIO4 - SERVO3_PIN - FIL_RUNOUT_PIN
+ {0xFF,0xFF}, //DIO5 - SERVO2_PIN
+ {0xFF,0xFF}, //DIO6 - SERVO1_PIN
+ {0xFF,0xFF}, //DIO7 -
+ {2, 7}, //DIO8 - RAMPS_D8_PIN
+ {2, 4}, //DIO9 - RAMPS_D9_PIN
+ {2, 5}, //DIO10 - RAMPS_D10_PIN
+ {0xFF,0xFF}, //DIO11 -
+ {2, 12}, //DIO12 - PS_ON_PIN
+ {4, 28}, //DIO13 - LED_PIN
+ {1, 26}, //DIO14 - Y_MIN_PIN
+ {1, 27}, //DIO15 - Y_MAX_PIN
+ {0, 16}, //DIO16 - LCD_PINS_RS
+ {0, 18}, //DIO17 - LCD_PINS_ENABLE
+ {1, 29}, //DIO18 - Z_MIN_PIN
+ {1, 28}, //DIO19 - Z_MAX_PIN
+ {0xFF,0xFF}, //DIO20
+ {0xFF,0xFF}, //DIO21
+ {0xFF,0xFF}, //DIO22
+ {0, 15}, //DIO23 - LCD_PINS_D4
+ {0, 4}, //DIO24 - E0_ENABLE_PIN
+ {0xFF,0xFF}, //DIO25
+ {2, 0}, //DIO26 - E0_STEP_PIN
+ {0xFF,0xFF}, //DIO27
+ {0, 5}, //DIO28 - E0_DIR_PIN
+ {0xFF,0xFF}, //DIO29
+ {4, 29}, //DIO30 - E1_ENABLE_PIN
+ {3, 26}, //DIO31 - BTN_EN1
+ {0xFF,0xFF}, //DIO32
+ {3, 25}, //DIO33 - BTN_EN2
+ {2, 13}, //DIO34 - E1_DIR_PIN
+ {2, 11}, //DIO35 - BTN_ENC
+ {2, 8}, //DIO36 - E1_STEP_PIN
+ {1, 30}, //DIO37 - BEEPER_PIN
+ {0, 10}, //DIO38 - X_ENABLE_PIN
+ {0xFF,0xFF}, //DIO39
+ {0xFF,0xFF}, //DIO40
+ {1, 22}, //DIO41 - KILL_PIN
+ {0xFF,0xFF}, //DIO42
+ {0xFF,0xFF}, //DIO43
+ {0xFF,0xFF}, //DIO44
+ {0xFF,0xFF}, //DIO45
+ {2, 3}, //DIO46 - Z_STEP_PIN
+ {0xFF,0xFF}, //DIO47
+ {0, 22}, //DIO48 - Z_DIR_PIN
+ {1, 31}, //DIO49 - SD_DETECT_PIN
+ {0, 17}, //DIO50 - MISO_PIN
+ {0, 18}, //DIO51 - MOSI_PIN
+ {0, 15}, //DIO52 - SCK_PIN
+ {1, 23}, //DIO53 - SDSS
+ {2, 1}, //DIO54 - X_STEP_PIN
+ {0, 11}, //DIO55 - X_DIR_PIN
+ {0, 19}, //DIO56 - Y_ENABLE_PIN
+ {0xFF,0xFF}, //DIO57
+ {0xFF,0xFF}, //DIO58
+ {0xFF,0xFF}, //DIO59
+ {2, 2}, //DIO60 - Y_STEP_PIN
+ {0, 20}, //DIO61 - Y_DIR_PIN
+ {0, 21}, //DIO62 - Z_ENABLE_PIN
+ {0xFF,0xFF}, //DIO63
+ {0xFF,0xFF}, //DIO64
+ {0xFF,0xFF}, //DIO65
+ {0xFF,0xFF}, //DIO66
+ {0xFF,0xFF}, //DIO67
+ {0xFF,0xFF}, //DIO68
+ {0xFF,0xFF}, //DIO69
+};
+
+// ***********************
+// Preprocessor pinmapping
+// ***********************
+
+// #define X_MAX_PIN 2
+#define DIO2_PORT 1
+#define DIO2_PIN 25
+// #define X_MIN_PIN 3
+#define DIO3_PORT 1
+#define DIO3_PIN 24
+// #define Y_MIN_PIN 14
+#define DIO14_PORT 1
+#define DIO14_PIN 26
+// #define Y_MAX_PIN 15
+#define DIO15_PORT 1
+#define DIO15_PIN 27
+// #define Z_MIN_PIN 18
+#define DIO18_PORT 1
+#define DIO18_PIN 29
+// #define Z_MAX_PIN 19
+#define DIO19_PORT 1
+#define DIO19_PIN 28
+// #define X_STEP_PIN 54
+#define DIO54_PORT 2
+#define DIO54_PIN 1
+// #define X_DIR_PIN 55
+#define DIO55_PORT 0
+#define DIO55_PIN 11
+// #define X_ENABLE_PIN 38
+#define DIO38_PORT 0
+#define DIO38_PIN 10
+// #define Y_STEP_PIN 60
+#define DIO60_PORT 2
+#define DIO60_PIN 2
+// #define Y_DIR_PIN 61
+#define DIO61_PORT 0
+#define DIO61_PIN 20
+// #define Y_ENABLE_PIN 56
+#define DIO56_PORT 0
+#define DIO56_PIN 19
+// #define Z_STEP_PIN 46
+#define DIO46_PORT 2
+#define DIO46_PIN 3
+// #define Z_DIR_PIN 48
+#define DIO48_PORT 0
+#define DIO48_PIN 22
+// #define Z_ENABLE_PIN 62
+#define DIO62_PORT 0
+#define DIO62_PIN 21
+// #define E0_STEP_PIN 26
+#define DIO26_PORT 2
+#define DIO26_PIN 0
+// #define E0_DIR_PIN 28
+#define DIO28_PORT 0
+#define DIO28_PIN 5
+// #define E0_ENABLE_PIN 24
+#define DIO24_PORT 0
+#define DIO24_PIN 4
+// #define E1_STEP_PIN 36
+#define DIO36_PORT 2
+#define DIO36_PIN 8
+// #define E1_DIR_PIN 34
+#define DIO34_PORT 2
+#define DIO34_PIN 13
+// #define E1_ENABLE_PIN 30
+#define DIO30_PORT 4
+#define DIO30_PIN 29
+// #define RAMPS_D8_PIN 8
+#define DIO8_PORT 2
+#define DIO8_PIN 7
+// #define RAMPS_D9_PIN 9
+#define DIO9_PORT 2
+#define DIO9_PIN 4
+// #define RAMPS_D10_PIN 10
+#define DIO10_PORT 2
+#define DIO10_PIN 5
+// #define MISO 50
+#define DIO50_PORT 0
+#define DIO50_PIN 17
+// #define MOSI 51
+#define DIO51_PORT 0
+#define DIO51_PIN 18
+// #define SCK 52
+#define DIO52_PORT 0
+#define DIO52_PIN 15
+// #define SDSS 53
+#define DIO53_PORT 1
+#define DIO53_PIN 23
+// #define LED_PIN 13
+#define DIO13_PORT 4
+#define DIO13_PIN 28
+// #define FIL_RUNOUT_PIN 4
+#define DIO4_PORT -1
+#define DIO4_PIN -1
+// #define PS_ON_PIN 12
+#define DIO12_PORT 2
+#define DIO12_PIN 12
+// #define LCD_PINS_RS 16
+#define DIO16_PORT 0
+#define DIO16_PIN 16
+// #define LCD_PINS_ENABLE 17
+#define DIO17_PORT 0
+#define DIO17_PIN 18
+// #define LCD_PINS_D4 23
+#define DIO23_PORT 0
+#define DIO23_PIN 15
+// #define BEEPER_PIN 37
+#define DIO37_PORT 1
+#define DIO37_PIN 30
+// #define BTN_EN1 31
+#define DIO31_PORT 3
+#define DIO31_PIN 26
+// #define BTN_EN2 33
+#define DIO33_PORT 3
+#define DIO33_PIN 25
+// #define BTN_ENC 35
+#define DIO35_PORT 2
+#define DIO35_PIN 11
+// #define SD_DETECT_PIN 49
+#define DIO49_PORT 1
+#define DIO49_PIN 31
+// #define KILL_PIN 41
+#define DIO41_PORT 1
+#define DIO41_PIN 22
+
+#endif //__PINMAP_RE_ARM_H__
diff --git a/Marlin/src/HAL/HAL_LPC1768/pinmapping.h b/Marlin/src/HAL/HAL_LPC1768/pinmapping.h
new file mode 100644
index 000000000000..a0d10a1e67e5
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/pinmapping.h
@@ -0,0 +1,43 @@
+/**
+ * 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 .
+ *
+ */
+
+#ifndef __HAL_PINMAPPING_H__
+#define __HAL_PINMAPPING_H__
+
+struct pin_data {
+ uint8_t port;
+ uint8_t pin;
+};
+
+struct adc_pin_data {
+ uint8_t port;
+ uint8_t pin;
+ uint8_t adc;
+};
+
+#ifdef IS_REARM
+ #include "pinmap_re_arm.h"
+#else
+ #error "HAL: LPC1768: No defined pinnmapping"
+#endif
+
+#endif //__HAL_PINMAPPING_H__
diff --git a/Marlin/src/HAL/HAL_LPC1768/re_arm.ld b/Marlin/src/HAL/HAL_LPC1768/re_arm.ld
new file mode 100644
index 000000000000..1123b11328df
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/re_arm.ld
@@ -0,0 +1,180 @@
+/* Linker script for mbed LPC1768 with smoothie bootloader*/
+MEMORY
+{
+/* FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 512K */
+ FLASH (rx) : ORIGIN = 16K, LENGTH = (512K - 16K)
+ RAM (rwx) : ORIGIN = 0x100000C8, LENGTH = (32K - 0xC8)
+
+ USB_RAM(rwx) : ORIGIN = 0x2007C000, LENGTH = 16K
+ ETH_RAM(rwx) : ORIGIN = 0x20080000, LENGTH = 16K
+}
+
+/* Linker script to place sections and symbol values. Should be used together
+ * with other linker script that defines memory regions FLASH and RAM.
+ * It references following symbols, which must be defined in code:
+ * Reset_Handler : Entry of reset handler
+ *
+ * It defines following symbols, which code can use without definition:
+ * __exidx_start
+ * __exidx_end
+ * __etext
+ * __data_start__
+ * __preinit_array_start
+ * __preinit_array_end
+ * __init_array_start
+ * __init_array_end
+ * __fini_array_start
+ * __fini_array_end
+ * __data_end__
+ * __bss_start__
+ * __bss_end__
+ * __end__
+ * end
+ * __HeapLimit
+ * __StackLimit
+ * __StackTop
+ * __stack
+ */
+ENTRY(Reset_Handler)
+
+SECTIONS
+{
+ .text :
+ {
+ KEEP(*(.isr_vector))
+ *(.text*)
+
+ KEEP(*(.init))
+ KEEP(*(.fini))
+
+ /* .ctors */
+ *crtbegin.o(.ctors)
+ *crtbegin?.o(.ctors)
+ *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
+ *(SORT(.ctors.*))
+ *(.ctors)
+
+ /* .dtors */
+ *crtbegin.o(.dtors)
+ *crtbegin?.o(.dtors)
+ *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
+ *(SORT(.dtors.*))
+ *(.dtors)
+
+ *(.rodata*)
+
+ KEEP(*(.eh_frame*))
+ } > FLASH
+
+ .ARM.extab :
+ {
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ } > FLASH
+
+ __exidx_start = .;
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } > FLASH
+ __exidx_end = .;
+
+ __etext = .;
+
+ .data : AT (__etext)
+ {
+ __data_start__ = .;
+ Image$$RW_IRAM1$$Base = .;
+ *(vtable)
+ *(.data*)
+
+ . = ALIGN(4);
+ /* preinit data */
+ PROVIDE (__preinit_array_start = .);
+ KEEP(*(.preinit_array))
+ PROVIDE (__preinit_array_end = .);
+
+ . = ALIGN(4);
+ /* init data */
+ PROVIDE (__init_array_start = .);
+ KEEP(*(SORT(.init_array.*)))
+ KEEP(*(.init_array))
+ PROVIDE (__init_array_end = .);
+
+
+ . = ALIGN(4);
+ /* finit data */
+ PROVIDE (__fini_array_start = .);
+ KEEP(*(SORT(.fini_array.*)))
+ KEEP(*(.fini_array))
+ PROVIDE (__fini_array_end = .);
+
+ . = ALIGN(4);
+ /* All data end */
+ __data_end__ = .;
+
+ } > RAM
+
+ .bss :
+ {
+ __bss_start__ = .;
+ *(.bss*)
+ *(COMMON)
+ __bss_end__ = .;
+ Image$$RW_IRAM1$$ZI$$Limit = . ;
+ } > RAM
+
+ .heap :
+ {
+ __end__ = .;
+ end = __end__;
+ *(.heap*)
+ __HeapLimit = .;
+ } > RAM
+
+ /* .stack_dummy section doesn't contains any symbols. It is only
+ * used for linker to calculate size of stack sections, and assign
+ * values to stack symbols later */
+ .stack_dummy :
+ {
+ *(.stack)
+ } > RAM
+
+ /* Set stack top to end of RAM, and stack limit move down by
+ * size of stack_dummy section */
+ __StackTop = ORIGIN(RAM) + LENGTH(RAM);
+ __StackLimit = __StackTop - SIZEOF(.stack_dummy);
+ PROVIDE(__stack = __StackTop);
+ PROVIDE(__heapLimit = __HeapLimit);
+ PROVIDE(__stackSize = __StackTop - __HeapLimit);
+
+ /* Area of memory, heap and stack, to fill on startup - 8 bytes at a time. */
+ __FillStart = ALIGN(__end__, 8);
+
+ /* Check if data + heap + stack exceeds RAM limit */
+ ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
+
+
+ /* Code can explicitly ask for data to be
+ placed in these higher RAM banks where
+ they will be left uninitialized.
+ */
+ .AHBSRAM0 (NOLOAD):
+ {
+ Image$$RW_IRAM2$$Base = . ;
+ PROVIDE(__AHB0_block_start = .);
+ *(AHBSRAM0)
+ Image$$RW_IRAM2$$ZI$$Limit = .;
+ PROVIDE(__AHB0_dyn_start = .);
+ PROVIDE(__AHB0_end = ORIGIN(USB_RAM) + LENGTH(USB_RAM));
+ } > USB_RAM
+
+ .AHBSRAM1 (NOLOAD):
+ {
+ Image$$RW_IRAM3$$Base = . ;
+ PROVIDE(__AHB1_block_start = .);
+ *(AHBSRAM1)
+ Image$$RW_IRAM3$$ZI$$Limit = .;
+ PROVIDE(__AHB1_dyn_start = .);
+ PROVIDE(__AHB1_end = ORIGIN(ETH_RAM) + LENGTH(ETH_RAM));
+ } > ETH_RAM
+}
diff --git a/Marlin/src/HAL/HAL_LPC1768/serial.h b/Marlin/src/HAL/HAL_LPC1768/serial.h
new file mode 100644
index 000000000000..012b3d8201a8
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/serial.h
@@ -0,0 +1,118 @@
+/**
+ * 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 .
+ *
+ */
+
+#ifndef HAL_SERIAL_H_
+#define HAL_SERIAL_H_
+
+class HalSerial {
+public:
+ Serial serial_port;
+ HalSerial(PinName tx, PinName rx): serial_port(tx, rx) {
+ }
+
+ void begin(int32_t baud) {
+ serial_port.baud(baud);
+ }
+
+ char read() {
+ return serial_port.getc();
+ }
+
+ void write(char c) {
+ serial_port.putc(c);
+ }
+
+ operator bool() {
+ return true;
+ }
+
+ uint16_t available() {
+ return serial_port.readable();
+ }
+
+ void flush() {
+ }
+
+ void print(const char value[]) {
+ serial_port.printf("%s" , value);
+ }
+ void print(char value, int = 0) {
+ serial_port.printf("%c" , value);
+ }
+ void print(unsigned char value, int = 0) {
+ serial_port.printf("%u" , value);
+ }
+ void print(int value, int = 0) {
+ serial_port.printf("%d" , value);
+ }
+ void print(unsigned int value, int = 0) {
+ serial_port.printf("%u" , value);
+ }
+ void print(long value, int = 0) {
+ serial_port.printf("%ld" , value);
+ }
+ void print(unsigned long value, int = 0) {
+ serial_port.printf("%lu" , value);
+ }
+
+ void print(float value, int round = 6) {
+ serial_port.printf("%f" , value);
+ }
+ void print(double value, int round = 6) {
+ serial_port.printf("%f" , value );
+ }
+
+ void println(const char value[]) {
+ serial_port.printf("%s\n" , value);
+ }
+ void println(char value, int = 0) {
+ serial_port.printf("%c\n" , value);
+ }
+ void println(unsigned char value, int = 0) {
+ serial_port.printf("%u\r\n" , value);
+ }
+ void println(int value, int = 0) {
+ serial_port.printf("%d\n" , value);
+ }
+ void println(unsigned int value, int = 0) {
+ serial_port.printf("%u\n" , value);
+ }
+ void println(long value, int = 0) {
+ serial_port.printf("%ld\n" , value);
+ }
+ void println(unsigned long value, int = 0) {
+ serial_port.printf("%lu\n" , value);
+ }
+ void println(float value, int round = 6) {
+ serial_port.printf("%f\n" , value );
+ }
+ void println(double value, int round = 6) {
+ serial_port.printf("%f\n" , value );
+ }
+ void println(void) {
+ print('\n');
+ }
+
+};
+
+
+#endif /* MARLIN_SRC_HAL_HAL_SERIAL_H_ */
diff --git a/Marlin/src/HAL/HAL_LPC1768/servotimers.h b/Marlin/src/HAL/HAL_LPC1768/servotimers.h
new file mode 100644
index 000000000000..c5566b26cffe
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/servotimers.h
@@ -0,0 +1,25 @@
+/*
+ Copyright (c) 2013 Arduino LLC. 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
+*/
+
+/**
+ * Defines for 16 bit timers used with Servo library
+ *
+ * If _useTimerX is defined then TimerX is a 32 bit timer on the current board
+ * timer16_Sequence_t enumerates the sequence that the timers should be allocated
+ * _Nbr_16timers indicates how many timers are available.
+ */
diff --git a/Marlin/src/HAL/HAL_LPC1768/spi_pins.h b/Marlin/src/HAL/HAL_LPC1768/spi_pins.h
new file mode 100644
index 000000000000..f3997838a3e9
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/spi_pins.h
@@ -0,0 +1,35 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * 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 .
+ *
+ */
+
+
+#ifndef SPI_PINS_LPC1768_H
+#define SPI_PINS_LPC1768_H
+
+#define SOFTWARE_SPI
+/** onboard SD card */
+//#define SCK_PIN P0_7
+//#define MISO_PIN P0_8
+//#define MOSI_PIN P0_9
+//#define SS_PIN P0_6
+/** external */
+#define SCK_PIN 52 //P0_15
+#define MISO_PIN 50 //P0_17
+#define MOSI_PIN 51 //P0_18
+#define SS_PIN 53 //P1_23
+#endif /* SPI_PINS_LPC1768_H */
diff --git a/Marlin/src/HAL/HAL_LPC1768/watchdog.cpp b/Marlin/src/HAL/HAL_LPC1768/watchdog.cpp
new file mode 100644
index 000000000000..2102a4239eb4
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/watchdog.cpp
@@ -0,0 +1,50 @@
+/**
+ * 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 .
+ *
+ */
+
+#ifdef TARGET_LPC1768
+
+#include "../../../MarlinConfig.h"
+
+#if ENABLED(USE_WATCHDOG)
+
+ #include "watchdog.h"
+
+ void watchdog_init(void) {
+ LPC_WDT->WDCLKSEL = 0x1; // Set CLK src to PCLK
+ LPC_WDT->WDTC = 4 * (SystemCoreClock / 16); // 4 second timeout (16 divisor = WD has a fixed /4 prescaler, PCLK default is /4)
+ LPC_WDT->WDMOD = 0x3; // Enabled and Reset
+ LPC_WDT->WDFEED = 0xAA; // Initial feed to start
+ LPC_WDT->WDFEED = 0x55;
+ }
+
+ void HAL_clear_reset_source(void) {
+ LPC_WDT->WDMOD &= ~(1 << 2);
+ }
+
+ uint8_t HAL_get_reset_source (void) {
+ if((LPC_WDT->WDMOD >> 2) & 1) return RST_WATCHDOG;
+ return RST_POWER_ON;
+ }
+
+#endif // USE_WATCHDOG
+
+#endif
diff --git a/Marlin/src/HAL/HAL_LPC1768/watchdog.h b/Marlin/src/HAL/HAL_LPC1768/watchdog.h
new file mode 100644
index 000000000000..db98ba1dc488
--- /dev/null
+++ b/Marlin/src/HAL/HAL_LPC1768/watchdog.h
@@ -0,0 +1,47 @@
+/**
+ * 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 .
+ *
+ */
+
+#ifndef WATCHDOG_LPC1768_H
+#define WATCHDOG_LPC1768_H
+
+#define RST_POWER_ON 1
+#define RST_EXTERNAL 2
+#define RST_BROWN_OUT 4
+#define RST_WATCHDOG 8
+
+// Initialize watchdog with a 4 second interrupt time
+void watchdog_init();
+
+// Reset watchdog. MUST be called at least every 4 seconds after the
+// first watchdog_init
+inline void watchdog_reset() {
+ LPC_WDT->WDFEED = 0xAA;
+ LPC_WDT->WDFEED = 0x55;
+}
+
+/** clear reset reason */
+void HAL_clear_reset_source (void);
+
+/** reset reason */
+uint8_t HAL_get_reset_source (void);
+
+#endif /* WATCHDOG_H */
diff --git a/Marlin/src/HAL/HAL_spi_pins.h b/Marlin/src/HAL/HAL_spi_pins.h
index cf87b2f48409..858e28f06ffd 100644
--- a/Marlin/src/HAL/HAL_spi_pins.h
+++ b/Marlin/src/HAL/HAL_spi_pins.h
@@ -33,6 +33,10 @@
#include "HAL_AVR/spi_pins.h"
+ #elif defined(TARGET_LPC1768)
+
+ #include "HAL_LPC1768/spi_pins.h"
+
#else
#error Unsupported Platform!