Shorter paths to HAL, ExtUI (#17156)

This commit is contained in:
Scott Lahteine
2020-03-13 16:29:29 -05:00
committed by GitHub
parent ad980a72f7
commit 6bead0c1b0
600 changed files with 228 additions and 227 deletions

View File

@ -0,0 +1,327 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 "../../core/macros.h"
#include "../../core/serial.h"
#include <stdarg.h>
#include "../shared/backtrace/unwinder.h"
#include "../shared/backtrace/unwmemaccess.h"
#include "watchdog.h"
#include <debug_frmwrk.h>
// Debug monitor that dumps to the Programming port all status when
// an exception or WDT timeout happens - And then resets the board
// All the Monitor routines must run with interrupts disabled and
// under an ISR execution context. That is why we cannot reuse the
// Serial interrupt routines or any C runtime, as we don't know the
// state we are when running them
// A SW memory barrier, to ensure GCC does not overoptimize loops
#define sw_barrier() __asm__ volatile("": : :"memory");
// (re)initialize UART0 as a monitor output to 250000,n,8,1
static void TXBegin() {
}
// Send character through UART with no interrupts
static void TX(char c) {
_DBC(c);
}
// Send String through UART
static void TX(const char* s) {
while (*s) TX(*s++);
}
static void TXDigit(uint32_t d) {
if (d < 10) TX((char)(d+'0'));
else if (d < 16) TX((char)(d+'A'-10));
else TX('?');
}
// Send Hex number thru UART
static void TXHex(uint32_t v) {
TX("0x");
for (uint8_t i = 0; i < 8; i++, v <<= 4)
TXDigit((v >> 28) & 0xF);
}
// Send Decimal number thru UART
static void TXDec(uint32_t v) {
if (!v) {
TX('0');
return;
}
char nbrs[14];
char *p = &nbrs[0];
while (v != 0) {
*p++ = '0' + (v % 10);
v /= 10;
}
do {
p--;
TX(*p);
} while (p != &nbrs[0]);
}
// Dump a backtrace entry
static bool UnwReportOut(void* ctx, const UnwReport* bte) {
int* p = (int*)ctx;
(*p)++;
TX('#'); TXDec(*p); TX(" : ");
TX(bte->name?bte->name:"unknown"); TX('@'); TXHex(bte->function);
TX('+'); TXDec(bte->address - bte->function);
TX(" PC:");TXHex(bte->address); TX('\n');
return true;
}
#ifdef UNW_DEBUG
void UnwPrintf(const char* format, ...) {
char dest[256];
va_list argptr;
va_start(argptr, format);
vsprintf(dest, format, argptr);
va_end(argptr);
TX(&dest[0]);
}
#endif
/* Table of function pointers for passing to the unwinder */
static const UnwindCallbacks UnwCallbacks = {
UnwReportOut,
UnwReadW,
UnwReadH,
UnwReadB
#ifdef UNW_DEBUG
,UnwPrintf
#endif
};
/**
* HardFaultHandler_C:
* This is called from the HardFault_HandlerAsm with a pointer the Fault stack
* as the parameter. We can then read the values from the stack and place them
* into local variables for ease of reading.
* We then read the various Fault Status and Address Registers to help decode
* cause of the fault.
* The function ends with a BKPT instruction to force control back into the debugger
*/
extern "C"
void HardFault_HandlerC(unsigned long *sp, unsigned long lr, unsigned long cause) {
static const char* causestr[] = {
"NMI","Hard","Mem","Bus","Usage","Debug","WDT","RSTC"
};
UnwindFrame btf;
// Dump report to the Programming port (interrupts are DISABLED)
TXBegin();
TX("\n\n## Software Fault detected ##\n");
TX("Cause: "); TX(causestr[cause]); TX('\n');
TX("R0 : "); TXHex(((unsigned long)sp[0])); TX('\n');
TX("R1 : "); TXHex(((unsigned long)sp[1])); TX('\n');
TX("R2 : "); TXHex(((unsigned long)sp[2])); TX('\n');
TX("R3 : "); TXHex(((unsigned long)sp[3])); TX('\n');
TX("R12 : "); TXHex(((unsigned long)sp[4])); TX('\n');
TX("LR : "); TXHex(((unsigned long)sp[5])); TX('\n');
TX("PC : "); TXHex(((unsigned long)sp[6])); TX('\n');
TX("PSR : "); TXHex(((unsigned long)sp[7])); TX('\n');
// Configurable Fault Status Register
// Consists of MMSR, BFSR and UFSR
TX("CFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED28)))); TX('\n');
// Hard Fault Status Register
TX("HFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED2C)))); TX('\n');
// Debug Fault Status Register
TX("DFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED30)))); TX('\n');
// Auxiliary Fault Status Register
TX("AFSR : "); TXHex((*((volatile unsigned long *)(0xE000ED3C)))); TX('\n');
// Read the Fault Address Registers. These may not contain valid values.
// Check BFARVALID/MMARVALID to see if they are valid values
// MemManage Fault Address Register
TX("MMAR : "); TXHex((*((volatile unsigned long *)(0xE000ED34)))); TX('\n');
// Bus Fault Address Register
TX("BFAR : "); TXHex((*((volatile unsigned long *)(0xE000ED38)))); TX('\n');
TX("ExcLR: "); TXHex(lr); TX('\n');
TX("ExcSP: "); TXHex((unsigned long)sp); TX('\n');
btf.sp = ((unsigned long)sp) + 8*4; // The original stack pointer
btf.fp = btf.sp;
btf.lr = ((unsigned long)sp[5]);
btf.pc = ((unsigned long)sp[6]) | 1; // Force Thumb, as CORTEX only support it
// Perform a backtrace
TX("\nBacktrace:\n\n");
int ctr = 0;
UnwindStart(&btf, &UnwCallbacks, &ctr);
// Disable all NVIC interrupts
NVIC->ICER[0] = 0xFFFFFFFF;
NVIC->ICER[1] = 0xFFFFFFFF;
// Relocate VTOR table to default position
SCB->VTOR = 0;
// Clear cause of reset to prevent entering smoothie bootstrap
HAL_clear_reset_source();
// Restart watchdog
#if ENABLED(USE_WATCHDOG)
//WDT_Restart(WDT);
watchdog_init();
#endif
// Reset controller
NVIC_SystemReset();
// Nothing below here is compiled because NVIC_SystemReset loops forever
for (;;) {
#if ENABLED(USE_WATCHDOG)
watchdog_init();
#endif
}
}
extern "C" {
__attribute__((naked)) void NMI_Handler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#0")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void HardFault_Handler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#1")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void MemManage_Handler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#2")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void BusFault_Handler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#3")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void UsageFault_Handler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#4")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void DebugMon_Handler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#5")
A("b HardFault_HandlerC")
);
}
/* This is NOT an exception, it is an interrupt handler - Nevertheless, the framing is the same */
__attribute__((naked)) void WDT_IRQHandler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#6")
A("b HardFault_HandlerC")
);
}
__attribute__((naked)) void RSTC_Handler() {
__asm__ __volatile__ (
".syntax unified" "\n\t"
A("tst lr, #4")
A("ite eq")
A("mrseq r0, msp")
A("mrsne r0, psp")
A("mov r1,lr")
A("mov r2,#7")
A("b HardFault_HandlerC")
);
}
}
#endif // TARGET_LPC1768

View File

@ -0,0 +1,87 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/MarlinConfig.h"
#include "../shared/Delay.h"
#include "../../../gcode/parser.h"
#if ENABLED(USE_WATCHDOG)
#include "watchdog.h"
#endif
uint32_t HAL_adc_reading = 0;
// U8glib required functions
extern "C" void u8g_xMicroDelay(uint16_t val) {
DELAY_US(val);
}
extern "C" void u8g_MicroDelay() {
u8g_xMicroDelay(1);
}
extern "C" void u8g_10MicroDelay() {
u8g_xMicroDelay(10);
}
extern "C" void u8g_Delay(uint16_t val) {
delay(val);
}
//************************//
// return free heap space
int freeMemory() {
char stack_end;
void *heap_start = malloc(sizeof(uint32_t));
if (heap_start == 0) return 0;
uint32_t result = (uint32_t)&stack_end - (uint32_t)heap_start;
free(heap_start);
return result;
}
// scan command line for code
// return index into pin map array if found and the pin is valid.
// return dval if not found or not a valid pin.
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100;
const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2;
return ind > -1 ? ind : dval;
}
void flashFirmware(int16_t value) {
NVIC_SystemReset();
}
void HAL_clear_reset_source(void) {
#if ENABLED(USE_WATCHDOG)
watchdog_clear_timeout_flag();
#endif
}
uint8_t HAL_get_reset_source(void) {
#if ENABLED(USE_WATCHDOG)
if (watchdog_timed_out()) return RST_WATCHDOG;
#endif
return RST_POWER_ON;
}
#endif // TARGET_LPC1768

View File

@ -0,0 +1,218 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 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 <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL_LPC1768/HAL.h
* Hardware Abstraction Layer for NXP LPC1768
*/
#define CPU_32_BIT
void HAL_init();
#include <stdint.h>
#include <stdarg.h>
#include <algorithm>
extern "C" volatile uint32_t _millis;
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "timers.h"
#include "MarlinSerial.h"
#include <adc.h>
#include <pinmapping.h>
#include <CDCSerial.h>
//
// Default graphical display delays
//
#ifndef ST7920_DELAY_1
#define ST7920_DELAY_1 DELAY_NS(600)
#endif
#ifndef ST7920_DELAY_2
#define ST7920_DELAY_2 DELAY_NS(750)
#endif
#ifndef ST7920_DELAY_3
#define ST7920_DELAY_3 DELAY_NS(750)
#endif
#if SERIAL_PORT == -1
#define MYSERIAL0 UsbSerial
#elif SERIAL_PORT == 0
#define MYSERIAL0 MSerial
#elif SERIAL_PORT == 1
#define MYSERIAL0 MSerial1
#elif SERIAL_PORT == 2
#define MYSERIAL0 MSerial2
#elif SERIAL_PORT == 3
#define MYSERIAL0 MSerial3
#else
#error "SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == SERIAL_PORT
#error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
#elif SERIAL_PORT_2 == -1
#define MYSERIAL1 UsbSerial
#elif SERIAL_PORT_2 == 0
#define MYSERIAL1 MSerial
#elif SERIAL_PORT_2 == 1
#define MYSERIAL1 MSerial1
#elif SERIAL_PORT_2 == 2
#define MYSERIAL1 MSerial2
#elif SERIAL_PORT_2 == 3
#define MYSERIAL1 MSerial3
#else
#error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration."
#endif
#define NUM_SERIAL 2
#else
#define NUM_SERIAL 1
#endif
#ifdef DGUS_SERIAL_PORT
#if DGUS_SERIAL_PORT == SERIAL_PORT
#error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
#elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
#error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
#elif DGUS_SERIAL_PORT == -1
#define DGUS_SERIAL UsbSerial
#elif DGUS_SERIAL_PORT == 0
#define DGUS_SERIAL MSerial
#elif DGUS_SERIAL_PORT == 1
#define DGUS_SERIAL MSerial1
#elif DGUS_SERIAL_PORT == 2
#define DGUS_SERIAL MSerial2
#elif DGUS_SERIAL_PORT == 3
#define DGUS_SERIAL MSerial3
#else
#error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration."
#endif
#endif
//
// Interrupts
//
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
#define CRITICAL_SECTION_END() if (!primask) __enable_irq()
#define ISRS_ENABLED() (!__get_PRIMASK())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
//
// Utility functions
//
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
int freeMemory();
#pragma GCC diagnostic pop
//
// ADC API
//
#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 (2) // 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)
#define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t
#define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
extern uint32_t HAL_adc_reading;
[[gnu::always_inline]] inline void HAL_start_adc(const pin_t pin) {
HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
}
[[gnu::always_inline]] inline uint16_t HAL_read_adc() {
return HAL_adc_reading;
}
#define HAL_adc_init()
#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
#define HAL_START_ADC(pin) HAL_start_adc(pin)
#define HAL_READ_ADC() HAL_read_adc()
#define HAL_ADC_READY() (true)
// Test whether the pin is valid
constexpr bool VALID_PIN(const pin_t pin) {
return LPC176x::pin_is_valid(pin);
}
// Get the analog index for a digital pin
constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t pin) {
return (LPC176x::pin_is_valid(pin) && LPC176x::pin_has_adc(pin)) ? pin : -1;
}
// Return the index of a pin number
constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) {
return LPC176x::pin_index(pin);
}
// Get the pin number at the given index
constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) {
return LPC176x::pin_index(index);
}
// Parse a G-code word into a pin index
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
// P0.6 thru P0.9 are for the onboard SD card
#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09
#define HAL_IDLETASK 1
void HAL_idletask();
#define PLATFORM_M997_SUPPORT
void flashFirmware(int16_t value);
/**
* set_pwm_frequency
* Set the frequency of the timer corresponding to the provided pin
* All Hardware PWM pins run at the same frequency and all
* Software PWM pins run at the same frequency
*/
void set_pwm_frequency(const pin_t pin, int f_desired);
/**
* set_pwm_duty
* Set the PWM duty cycle of the provided pin to the provided value
* Optionally allows inverting the duty cycle [default = false]
* Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
*/
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
// Reset source
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);

View File

@ -0,0 +1,240 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
*/
/**
* Hardware SPI and a software SPI implementations are included in this file.
* The hardware SPI runs faster and has higher throughput but is not compatible
* with some LCD interfaces/adapters.
*
* Control of the slave select pin(s) is handled by the calling routines.
*
* Some of the LCD interfaces/adapters result in the LCD SPI and the SD card
* SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with
* WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is
* active. If any of these pins are shared then the software SPI must be used.
*
* A more sophisticated hardware SPI can be found at the following link. This
* implementation has not been fully debugged.
* https://github.com/MarlinFirmware/Marlin/tree/071c7a78f27078fd4aee9a3ef365fcf5e143531e
*/
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
#include <SPI.h>
// ------------------------
// Public functions
// ------------------------
#if ENABLED(LPC_SOFTWARE_SPI)
#include <SoftwareSPI.h>
// Software SPI
static uint8_t SPI_speed = 0;
static uint8_t spiTransfer(uint8_t b) {
return swSpiTransfer(b, SPI_speed, SCK_PIN, MISO_PIN, MOSI_PIN);
}
void spiBegin() {
swSpiBegin(SCK_PIN, MISO_PIN, MOSI_PIN);
}
void spiInit(uint8_t spiRate) {
SPI_speed = swSpiInit(spiRate, SCK_PIN, MOSI_PIN);
}
uint8_t spiRec() { return spiTransfer(0xFF); }
void spiRead(uint8_t*buf, uint16_t nbyte) {
for (int i = 0; i < nbyte; i++)
buf[i] = spiTransfer(0xFF);
}
void spiSend(uint8_t b) { (void)spiTransfer(b); }
void spiSend(const uint8_t* buf, size_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++)
(void)spiTransfer(buf[i]);
}
void spiSendBlock(uint8_t token, const uint8_t* buf) {
(void)spiTransfer(token);
for (uint16_t i = 0; i < 512; i++)
(void)spiTransfer(buf[i]);
}
#else
// Hardware SPI
#include <lpc17xx_pinsel.h>
#include <lpc17xx_ssp.h>
#include <lpc17xx_clkpwr.h>
// decide which HW SPI device to use
#ifndef LPC_HW_SPI_DEV
#if (SCK_PIN == P0_07 && MISO_PIN == P0_08 && MOSI_PIN == P0_09)
#define LPC_HW_SPI_DEV 1
#else
#if (SCK_PIN == P0_15 && MISO_PIN == P0_17 && MOSI_PIN == P0_18)
#define LPC_HW_SPI_DEV 0
#else
#error "Invalid pins selected for hardware SPI"
#endif
#endif
#endif
#if (LPC_HW_SPI_DEV == 0)
#define LPC_SSPn LPC_SSP0
#else
#define LPC_SSPn LPC_SSP1
#endif
void spiBegin() { // setup SCK, MOSI & MISO pins for SSP0
PINSEL_CFG_Type PinCfg; // data structure to hold init values
PinCfg.Funcnum = 2;
PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
PinCfg.Pinnum = LPC176x::pin_bit(SCK_PIN);
PinCfg.Portnum = LPC176x::pin_port(SCK_PIN);
PINSEL_ConfigPin(&PinCfg);
SET_OUTPUT(SCK_PIN);
PinCfg.Pinnum = LPC176x::pin_bit(MISO_PIN);
PinCfg.Portnum = LPC176x::pin_port(MISO_PIN);
PINSEL_ConfigPin(&PinCfg);
SET_INPUT(MISO_PIN);
PinCfg.Pinnum = LPC176x::pin_bit(MOSI_PIN);
PinCfg.Portnum = LPC176x::pin_port(MOSI_PIN);
PINSEL_ConfigPin(&PinCfg);
SET_OUTPUT(MOSI_PIN);
// divide PCLK by 2 for SSP0
CLKPWR_SetPCLKDiv(LPC_HW_SPI_DEV == 0 ? CLKPWR_PCLKSEL_SSP0 : CLKPWR_PCLKSEL_SSP1, CLKPWR_PCLKSEL_CCLK_DIV_2);
spiInit(0);
SSP_Cmd(LPC_SSPn, ENABLE); // start SSP running
}
void spiInit(uint8_t spiRate) {
// table to convert Marlin spiRates (0-5 plus default) into bit rates
uint32_t Marlin_speed[7]; // CPSR is always 2
Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED
Marlin_speed[1] = 4166667; //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED
Marlin_speed[2] = 2083333; //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED
Marlin_speed[3] = 1000000; //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED
Marlin_speed[4] = 500000; //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5
Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6
Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h
// setup for SPI mode
SSP_CFG_Type HW_SPI_init; // data structure to hold init values
SSP_ConfigStructInit(&HW_SPI_init); // set values for SPI mode
HW_SPI_init.ClockRate = Marlin_speed[_MIN(spiRate, 6)]; // put in the specified bit rate
HW_SPI_init.Mode |= SSP_CR1_SSP_EN;
SSP_Init(LPC_SSPn, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers
}
static uint8_t doio(uint8_t b) {
/* send and receive a single byte */
SSP_SendData(LPC_SSPn, b & 0x00FF);
while (SSP_GetStatus(LPC_SSPn, SSP_STAT_BUSY)); // wait for it to finish
return SSP_ReceiveData(LPC_SSPn) & 0x00FF;
}
void spiSend(uint8_t b) { doio(b); }
void spiSend(const uint8_t* buf, size_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++) doio(buf[i]);
}
void spiSend(uint32_t chan, byte b) {
}
void spiSend(uint32_t chan, const uint8_t* buf, size_t nbyte) {
}
// Read single byte from SPI
uint8_t spiRec() { return doio(0xFF); }
uint8_t spiRec(uint32_t chan) { return 0; }
// Read from SPI into buffer
void spiRead(uint8_t *buf, uint16_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++) buf[i] = doio(0xFF);
}
static uint8_t spiTransfer(uint8_t b) {
return doio(b);
}
// Write from buffer to SPI
void spiSendBlock(uint8_t token, const uint8_t* buf) {
(void)spiTransfer(token);
for (uint16_t i = 0; i < 512; i++)
(void)spiTransfer(buf[i]);
}
/** Begin SPI transaction, set clock, bit order, data mode */
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) {
// TODO: to be implemented
}
#endif // ENABLED(LPC_SOFTWARE_SPI)
void SPIClass::begin() { spiBegin(); }
void SPIClass::beginTransaction(SPISettings cfg) {
uint8_t spiRate;
switch (cfg.spiRate()) {
case 8000000: spiRate = 0; break;
case 4000000: spiRate = 1; break;
case 2000000: spiRate = 2; break;
case 1000000: spiRate = 3; break;
case 500000: spiRate = 4; break;
case 250000: spiRate = 5; break;
case 125000: spiRate = 6; break;
default: spiRate = 2; break;
}
spiInit(spiRate);
}
uint8_t SPIClass::transfer(const uint8_t B) { return spiTransfer(B); }
uint16_t SPIClass::transfer16(const uint16_t data) {
return (transfer((data >> 8) & 0xFF) << 8)
| (transfer(data & 0xFF) & 0xFF);
}
SPIClass SPI;
#endif // TARGET_LPC1768

View File

@ -0,0 +1,56 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0)
MarlinSerial MSerial(LPC_UART0);
extern "C" void UART0_IRQHandler() {
MSerial.IRQHandler();
}
#endif
#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1
MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
extern "C" void UART1_IRQHandler() {
MSerial1.IRQHandler();
}
#endif
#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2
MarlinSerial MSerial2(LPC_UART2);
extern "C" void UART2_IRQHandler() {
MSerial2.IRQHandler();
}
#endif
#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3
MarlinSerial MSerial3(LPC_UART3);
extern "C" void UART3_IRQHandler() {
MSerial3.IRQHandler();
}
#endif
#endif // TARGET_LPC1768

View File

@ -0,0 +1,67 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
#include <HardwareSerial.h>
#include <WString.h>
#include "../../inc/MarlinConfigPre.h"
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/e_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
{
}
void end() {}
#if ENABLED(EMERGENCY_PARSER)
bool recv_callback(const char c) override {
emergency_parser.update(emergency_state, c);
return true; // do not discard character
}
EmergencyParser::State emergency_state;
#endif
};
extern MarlinSerial MSerial;
extern MarlinSerial MSerial1;
extern MarlinSerial MSerial2;
extern MarlinSerial MSerial3;

View File

@ -0,0 +1,71 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
* Copyright (c) 2009 Michael Margolis. 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
*/
#pragma once
/**
* Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers -
* Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
*
* The only modification was to update/delete macros to match the LPC176x.
*
*/
#include <Servo.h>
class libServo: public Servo {
public:
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 (attach(servo_info[servoIndex].Pin.nbr) >= 0) { // try to reattach
write(value);
safe_delay(servo_delay[servoIndex]); // delay to allow servo to reach position
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
detach();
#endif
}
}
};
#define HAL_SERVO_LIB libServo

View File

@ -0,0 +1,125 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the temperature-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)
*/
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
#define LPC1768_PIN_INTERRUPT_M(pin) ((pin >> 0x5 & 0x7) == 0 || (pin >> 0x5 & 0x7) == 2)
#if HAS_X_MAX
#if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN)
#error "X_MAX_PIN is not INTERRUPT-capable."
#endif
_ATTACH(X_MAX_PIN);
#endif
#if HAS_X_MIN
#if !LPC1768_PIN_INTERRUPT_M(X_MIN_PIN)
#error "X_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(X_MIN_PIN);
#endif
#if HAS_Y_MAX
#if !LPC1768_PIN_INTERRUPT_M(Y_MAX_PIN)
#error "Y_MAX_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Y_MAX_PIN);
#endif
#if HAS_Y_MIN
#if !LPC1768_PIN_INTERRUPT_M(Y_MIN_PIN)
#error "Y_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Y_MIN_PIN);
#endif
#if HAS_Z_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z_MAX_PIN)
#error "Z_MAX_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z_MAX_PIN);
#endif
#if HAS_Z_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PIN)
#error "Z_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z_MIN_PIN);
#endif
#if HAS_Z2_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z2_MAX_PIN)
#error "Z2_MAX_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z2_MAX_PIN);
#endif
#if HAS_Z2_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z2_MIN_PIN)
#error "Z2_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z2_MIN_PIN);
#endif
#if HAS_Z3_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z3_MAX_PIN)
#error "Z3_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z3_MAX_PIN);
#endif
#if HAS_Z3_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z3_MIN_PIN)
#error "Z3_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z3_MIN_PIN);
#endif
#if HAS_Z4_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z4_MAX_PIN)
#error "Z4_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z4_MIN_PIN)
#error "Z4_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z4_MIN_PIN);
#endif
#if HAS_Z_MIN_PROBE_PIN
#if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN)
#error "Z_MIN_PROBE_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z_MIN_PROBE_PIN);
#endif
}

View File

@ -0,0 +1,40 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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"
#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_PWM
#include <pwm.h>
void set_pwm_frequency(const pin_t pin, int f_desired) {
LPC176x::pwm_set_frequency(pin, f_desired);
}
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size);
}
#endif // FAST_PWM_FAN || SPINDLE_LASER_PWM
#endif // TARGET_LPC1768

View File

@ -0,0 +1,119 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* Fast I/O Routines for LPC1768/9
* Use direct port manipulation to save scads of processor time.
* Contributed by Triffid_Hunter and modified by Kliment, thinkyhead, Bob-the-Kuhn, et.al.
*/
/**
* Description: Fast IO functions LPC1768
*
* For TARGET LPC1768
*/
#include "../shared/Marduino.h"
#define PWM_PIN(P) true // all pins are PWM capable
#define LPC_PIN(pin) LPC176x::gpio_pin(pin)
#define LPC_GPIO(port) LPC176x::gpio_port(port)
#define SET_DIR_INPUT(IO) LPC176x::gpio_set_input(IO)
#define SET_DIR_OUTPUT(IO) LPC176x::gpio_set_output(IO)
#define SET_MODE(IO, mode) pinMode(IO, mode)
#define WRITE_PIN_SET(IO) LPC176x::gpio_set(IO)
#define WRITE_PIN_CLR(IO) LPC176x::gpio_clear(IO)
#define READ_PIN(IO) LPC176x::gpio_get(IO)
#define WRITE_PIN(IO,V) LPC176x::gpio_set(IO, V)
/**
* Magic I/O routines
*
* Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW);
*
* Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
*/
/// Read a pin
#define _READ(IO) READ_PIN(IO)
/// Write to a pin
#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) pinMode(IO, (V) ? INPUT_PULLUP : INPUT)
/// set pin as input with pulldown mode
#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT)
/// check if pin is an input
#define _IS_INPUT(IO) (!LPC176x::gpio_get_dir(IO))
/// check if pin is an output
#define _IS_OUTPUT(IO) (LPC176x::gpio_get_dir(IO))
/// Read a pin wrapper
#define READ(IO) _READ(IO)
/// Write to a pin wrapper
#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 input with pulldown wrapper
#define SET_INPUT_PULLDOWN(IO) do{ _SET_INPUT(IO); _PULLDOWN(IO, HIGH); }while(0)
/// set pin as output wrapper - reads the pin and sets the output to that value
#define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0)
// set pin as PWM
#define SET_PWM(IO) SET_OUTPUT(IO)
/// check if pin is an input wrapper
#define IS_INPUT(IO) _IS_INPUT(IO)
/// check if pin is an output wrapper
#define IS_OUTPUT(IO) _IS_OUTPUT(IO)
// Shorthand
#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)

View File

@ -0,0 +1,22 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once

View File

@ -0,0 +1,22 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once

View File

@ -0,0 +1,30 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
#if ENABLED(EEPROM_SETTINGS)
#undef USE_REAL_EEPROM
#define USE_EMULATED_EEPROM 1
#if DISABLED(FLASH_EEPROM_EMULATION)
#define SDCARD_EEPROM_EMULATION 1
#endif
#endif

View File

@ -0,0 +1,253 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
#if PIO_PLATFORM_VERSION < 1001
#error "nxplpc-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries. You may need to remove the platform and let it reinstall automatically."
#endif
#if PIO_FRAMEWORK_VERSION < 2002
#error "framework-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries."
#endif
/**
* Detect an old pins file by checking for old ADC pins values.
*/
#define _OLD_TEMP_PIN(P) PIN_EXISTS(P) && _CAT(P,_PIN) <= 7 && _CAT(P,_PIN) != 2 && _CAT(P,_PIN) != 3
#if _OLD_TEMP_PIN(TEMP_BED)
#error "TEMP_BED_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_0)
#error "TEMP_0_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_1)
#error "TEMP_1_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_2)
#error "TEMP_2_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_3)
#error "TEMP_3_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_4)
#error "TEMP_4_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_5)
#error "TEMP_5_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_6)
#error "TEMP_6_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#elif _OLD_TEMP_PIN(TEMP_7)
#error "TEMP_7_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
#endif
#undef _OLD_TEMP_PIN
/**
* Because PWM hardware channels all share the same frequency, along with the
* fallback software channels, FAST_PWM_FAN is incompatible with Servos.
*/
static_assert(!(NUM_SERVOS && ENABLED(FAST_PWM_FAN)), "BLTOUCH and Servos are incompatible with FAST_PWM_FAN on LPC176x boards.");
/**
* Test LPC176x-specific configuration values for errors at compile-time.
*/
//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
//#endif
#if MB(RAMPS_14_RE_ARM_EFB, RAMPS_14_RE_ARM_EEB, RAMPS_14_RE_ARM_EFF, RAMPS_14_RE_ARM_EEF, RAMPS_14_RE_ARM_SF)
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI)
#error "Re-ARM with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER and TMC2130 requires TMC_USE_SW_SPI."
#endif
#endif
static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported on LPC176x.");
/**
* Flag any serial port conflicts
*
* Port | TX | RX |
* --- | --- | --- |
* Serial | P0_02 | P0_03 |
* Serial1 | P0_15 | P0_16 |
* Serial2 | P0_10 | P0_11 |
* Serial3 | P0_00 | P0_01 |
*/
#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0)
#define IS_TX0(P) (P == P0_02)
#define IS_RX0(P) (P == P0_03)
#if IS_TX0(TMC_SW_MISO) || IS_RX0(TMC_SW_MOSI)
#error "Serial port pins (0) conflict with Trinamic SPI pins!"
#elif ENABLED(MK2_MULTIPLEXER) && (IS_TX0(E_MUX1_PIN) || IS_RX0(E_MUX0_PIN))
#error "Serial port pins (0) conflict with MK2 multiplexer pins!"
#elif (AXIS_HAS_SPI(X) && IS_TX0(X_CS_PIN)) || (AXIS_HAS_SPI(Y) && IS_RX0(Y_CS_PIN))
#error "Serial port pins (0) conflict with X/Y axis SPI pins!"
#endif
#undef IS_TX0
#undef IS_RX0
#endif
#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1
#define IS_TX1(P) (P == P0_15)
#define IS_RX1(P) (P == P0_16)
#if IS_TX1(TMC_SW_SCK)
#error "Serial port pins (1) conflict with other pins!"
#elif HAS_SPI_LCD
#if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1)
#error "Serial port pins (1) conflict with Encoder Buttons!"
#elif IS_TX1(SCK_PIN) || IS_TX1(LCD_PINS_D4) || IS_TX1(DOGLCD_SCK) || IS_TX1(LCD_RESET_PIN) || IS_TX1(LCD_PINS_RS) || IS_TX1(SHIFT_CLK) \
|| IS_RX1(LCD_SDSS) || IS_RX1(LCD_PINS_RS) || IS_RX1(MISO_PIN) || IS_RX1(DOGLCD_A0) || IS_RX1(SS_PIN) || IS_RX1(LCD_SDSS) || IS_RX1(DOGLCD_CS) || IS_RX1(LCD_RESET_PIN) || IS_RX1(LCD_BACKLIGHT_PIN)
#error "Serial port pins (1) conflict with LCD pins!"
#endif
#endif
#undef IS_TX1
#undef IS_RX1
#endif
#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2
#define IS_TX2(P) (P == P0_10)
#define IS_RX2(P) (P == P0_11)
#if IS_TX2(X2_ENABLE_PIN) || IS_RX2(X2_DIR_PIN) || IS_RX2(X2_STEP_PIN) || (AXIS_HAS_SPI(X2) && IS_TX2(X2_CS_PIN))
#error "Serial port pins (2) conflict with X2 pins!"
#elif IS_TX2(Y2_ENABLE_PIN) || IS_RX2(Y2_DIR_PIN) || IS_RX2(Y2_STEP_PIN) || (AXIS_HAS_SPI(Y2) && IS_TX2(Y2_CS_PIN))
#error "Serial port pins (2) conflict with Y2 pins!"
#elif IS_TX2(Z2_ENABLE_PIN) || IS_RX2(Z2_DIR_PIN) || IS_RX2(Z2_STEP_PIN) || (AXIS_HAS_SPI(Z2) && IS_TX2(Z2_CS_PIN))
#error "Serial port pins (2) conflict with Z2 pins!"
#elif IS_TX2(Z3_ENABLE_PIN) || IS_RX2(Z3_DIR_PIN) || IS_RX2(Z3_STEP_PIN) || (AXIS_HAS_SPI(Z3) && IS_TX2(Z3_CS_PIN))
#error "Serial port pins (2) conflict with Z3 pins!"
#elif IS_TX2(Z4_ENABLE_PIN) || IS_RX2(Z4_DIR_PIN) || IS_RX2(Z4_STEP_PIN) || (AXIS_HAS_SPI(Z4) && IS_TX2(Z4_CS_PIN))
#error "Serial port pins (2) conflict with Z4 pins!"
#elif IS_RX2(X_DIR_PIN) || IS_RX2(Y_DIR_PIN)
#error "Serial port pins (2) conflict with other pins!"
#elif Y_HOME_DIR < 0 && IS_TX2(Y_STOP_PIN)
#error "Serial port pins (2) conflict with Y endstop pin!"
#elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN)
#error "Serial port pins (2) conflict with probe pin!"
#elif IS_TX2(X_ENABLE_PIN) || IS_RX2(X_DIR_PIN) || IS_TX2(Y_ENABLE_PIN) || IS_RX2(Y_DIR_PIN)
#error "Serial port pins (2) conflict with X/Y stepper pins!"
#elif EXTRUDERS > 1 && (IS_TX2(E1_ENABLE_PIN) || (AXIS_HAS_SPI(E1) && IS_TX2(E1_CS_PIN)))
#error "Serial port pins (2) conflict with E1 stepper pins!"
#elif EXTRUDERS && (IS_RX2(E0_DIR_PIN) || IS_RX2(E0_STEP_PIN))
#error "Serial port pins (2) conflict with E stepper pins!"
#endif
#undef IS_TX2
#undef IS_RX2
#endif
#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3
#define PIN_IS_TX3(P) (PIN_EXISTS(P) && P##_PIN == P0_00)
#define PIN_IS_RX3(P) (P##_PIN == P0_01)
#if PIN_IS_TX3(X_MIN) || PIN_IS_RX3(X_MAX)
#error "Serial port pins (3) conflict with X endstop pins!"
#elif PIN_IS_TX3(Y_SERIAL_TX) || PIN_IS_TX3(Y_SERIAL_RX) \
|| PIN_IS_RX3(X_SERIAL_TX) || PIN_IS_RX3(X_SERIAL_RX)
#error "Serial port pins (3) conflict with X/Y axis UART pins!"
#elif PIN_IS_TX3(X2_DIR) || PIN_IS_RX3(X2_STEP)
#error "Serial port pins (3) conflict with X2 pins!"
#elif PIN_IS_TX3(Y2_DIR) || PIN_IS_RX3(Y2_STEP)
#error "Serial port pins (3) conflict with Y2 pins!"
#elif PIN_IS_TX3(Z2_DIR) || PIN_IS_RX3(Z2_STEP)
#error "Serial port pins (3) conflict with Z2 pins!"
#elif PIN_IS_TX3(Z3_DIR) || PIN_IS_RX3(Z3_STEP)
#error "Serial port pins (3) conflict with Z3 pins!"
#elif PIN_IS_TX3(Z4_DIR) || PIN_IS_RX3(Z4_STEP)
#error "Serial port pins (3) conflict with Z4 pins!"
#elif EXTRUDERS > 1 && (PIN_IS_TX3(E1_DIR) || PIN_IS_RX3(E1_STEP))
#error "Serial port pins (3) conflict with E1 pins!"
#endif
#undef PIN_IS_TX3
#undef PIN_IS_RX3
#endif
//
// Flag any i2c pin conflicts
//
#if ANY(DIGIPOT_I2C, DIGIPOT_MCP4018, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM)
#define USEDI2CDEV_M 1 // <Arduino>/Wire.cpp
#if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1)
#define PIN_IS_SDA0(P) (P##_PIN == P0_27)
#define IS_SCL0(P) (P == P0_28)
#if ENABLED(SDSUPPORT) && PIN_IS_SDA0(SD_DETECT)
#error "SDA0 overlaps with SD_DETECT_PIN!"
#elif PIN_IS_SDA0(E0_AUTO_FAN)
#error "SDA0 overlaps with E0_AUTO_FAN_PIN!"
#elif PIN_IS_SDA0(BEEPER)
#error "SDA0 overlaps with BEEPER_PIN!"
#elif IS_SCL0(BTN_ENC)
#error "SCL0 overlaps with Encoder Button!"
#elif IS_SCL0(SS_PIN)
#error "SCL0 overlaps with SS_PIN!"
#elif IS_SCL0(LCD_SDSS)
#error "SCL0 overlaps with LCD_SDSS!"
#endif
#undef PIN_IS_SDA0
#undef IS_SCL0
#elif USEDI2CDEV_M == 1 // P0_00 [D20] (SCA) ............ P0_01 [D21] (SCL)
#define PIN_IS_SDA1(P) (PIN_EXISTS(P) && P##_PIN == P0_00)
#define PIN_IS_SCL1(P) (P##_PIN == P0_01)
#if PIN_IS_SDA1(X_MIN) || PIN_IS_SCL1(X_MAX)
#error "One or more i2c (1) pins overlaps with X endstop pins! Disable i2c peripherals."
#elif PIN_IS_SDA1(X2_DIR) || PIN_IS_SCL1(X2_STEP)
#error "One or more i2c (1) pins overlaps with X2 pins! Disable i2c peripherals."
#elif PIN_IS_SDA1(Y2_DIR) || PIN_IS_SCL1(Y2_STEP)
#error "One or more i2c (1) pins overlaps with Y2 pins! Disable i2c peripherals."
#elif PIN_IS_SDA1(Z2_DIR) || PIN_IS_SCL1(Z2_STEP)
#error "One or more i2c (1) pins overlaps with Z2 pins! Disable i2c peripherals."
#elif PIN_IS_SDA1(Z3_DIR) || PIN_IS_SCL1(Z3_STEP)
#error "One or more i2c (1) pins overlaps with Z3 pins! Disable i2c peripherals."
#elif PIN_IS_SDA1(Z4_DIR) || PIN_IS_SCL1(Z4_STEP)
#error "One or more i2c (1) pins overlaps with Z4 pins! Disable i2c peripherals."
#elif EXTRUDERS > 1 && (PIN_IS_SDA1(E1_DIR) || PIN_IS_SCL1(E1_STEP))
#error "One or more i2c (1) pins overlaps with E1 pins! Disable i2c peripherals."
#endif
#undef PIN_IS_SDA1
#undef PIN_IS_SCL1
#elif USEDI2CDEV_M == 2 // P0_10 [D38] (X_ENABLE_PIN) ... P0_11 [D55] (X_DIR_PIN)
#define PIN_IS_SDA2(P) (P##_PIN == P0_10)
#define PIN_IS_SCL2(P) (P##_PIN == P0_11)
#if PIN_IS_SDA2(Y_STOP)
#error "i2c SDA2 overlaps with Y endstop pin!"
#elif HAS_CUSTOM_PROBE_PIN && PIN_IS_SDA2(Z_MIN_PROBE)
#error "i2c SDA2 overlaps with Z probe pin!"
#elif PIN_IS_SDA2(X_ENABLE) || PIN_IS_SDA2(Y_ENABLE)
#error "i2c SDA2 overlaps with X/Y ENABLE pin!"
#elif AXIS_HAS_SPI(X) && PIN_IS_SDA2(X_CS)
#error "i2c SDA2 overlaps with X CS pin!"
#elif PIN_IS_SDA2(X2_ENABLE)
#error "i2c SDA2 overlaps with X2 enable pin! Disable i2c peripherals."
#elif PIN_IS_SDA2(Y2_ENABLE)
#error "i2c SDA2 overlaps with Y2 enable pin! Disable i2c peripherals."
#elif PIN_IS_SDA2(Z2_ENABLE)
#error "i2c SDA2 overlaps with Z2 enable pin! Disable i2c peripherals."
#elif PIN_IS_SDA2(Z3_ENABLE)
#error "i2c SDA2 overlaps with Z3 enable pin! Disable i2c peripherals."
#elif PIN_IS_SDA2(Z4_ENABLE)
#error "i2c SDA2 overlaps with Z4 enable pin! Disable i2c peripherals."
#elif EXTRUDERS > 1 && PIN_IS_SDA2(E1_ENABLE)
#error "i2c SDA2 overlaps with E1 enable pin! Disable i2c peripherals."
#elif EXTRUDERS > 1 && AXIS_HAS_SPI(E1) && PIN_IS_SDA2(E1_CS)
#error "i2c SDA2 overlaps with E1 CS pin! Disable i2c peripherals."
#elif EXTRUDERS && (PIN_IS_SDA2(E0_STEP) || PIN_IS_SDA2(E0_DIR))
#error "i2c SCL2 overlaps with E0 STEP/DIR pin! Disable i2c peripherals."
#elif PIN_IS_SDA2(X_DIR) || PIN_IS_SDA2(Y_DIR)
#error "One or more i2c pins overlaps with X/Y DIR pin! Disable i2c peripherals."
#endif
#undef PIN_IS_SDA2
#undef PIN_IS_SCL2
#endif
#undef USEDI2CDEV_M
#endif

View File

@ -0,0 +1,48 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
#include "../../shared/HAL_SPI.h"
#include <stdint.h>
#define MSBFIRST 1
#define SPI_MODE3 0
class SPISettings {
public:
SPISettings(uint32_t speed, int, int) : spi_speed(speed) {};
uint32_t spiRate() { return spi_speed; }
private:
uint32_t spi_speed;
};
class SPIClass {
public:
void begin();
void beginTransaction(SPISettings);
void endTransaction() {};
uint8_t transfer(uint8_t data);
uint16_t transfer16(uint16_t data);
};
extern SPIClass SPI;

View File

@ -0,0 +1,106 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
/**
* digipot_mcp4451_I2C_routines.c
* Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfigPre.h"
#if MB(MKS_SBASE)
#ifdef __cplusplus
extern "C" {
#endif
#include "digipot_mcp4451_I2C_routines.h"
// These two routines are exact copies of the lpc17xx_i2c.c routines. Couldn't link to
// to the lpc17xx_i2c.c routines so had to copy them into this file & rename them.
static uint32_t _I2C_Start(LPC_I2C_TypeDef *I2Cx) {
// Reset STA, STO, SI
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC|I2C_I2CONCLR_STOC|I2C_I2CONCLR_STAC;
// Enter to Master Transmitter mode
I2Cx->I2CONSET = I2C_I2CONSET_STA;
// Wait for complete
while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
}
static void _I2C_Stop(LPC_I2C_TypeDef *I2Cx) {
// Make sure start bit is not active
if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
I2Cx->I2CONSET = I2C_I2CONSET_STO|I2C_I2CONSET_AA;
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
}
I2C_M_SETUP_Type transferMCfg;
#define I2C_status (LPC_I2C1->I2STAT & I2C_STAT_CODE_BITMASK)
uint8_t digipot_mcp4451_start(uint8_t sla) { // send slave address and write bit
// Sometimes TX data ACK or NAK status is returned. That mean the start state didn't
// happen which means only the value of the slave address was send. Keep looping until
// the slave address and write bit are actually sent.
do {
_I2C_Stop(I2CDEV_M); // output stop state on I2C bus
_I2C_Start(I2CDEV_M); // output start state on I2C bus
while ((I2C_status != I2C_I2STAT_M_TX_START)
&& (I2C_status != I2C_I2STAT_M_TX_RESTART)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_NACK)); //wait for start to be asserted
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_STAC; // clear start state before tansmitting slave address
LPC_I2C1->I2DAT = (sla << 1) & I2C_I2DAT_BITMASK; // transmit slave address & write bit
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
while ((I2C_status != I2C_I2STAT_M_TX_SLAW_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_SLAW_NACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_NACK)) { /* wait for slaw to finish */ }
} while ( (I2C_status == I2C_I2STAT_M_TX_DAT_ACK) || (I2C_status == I2C_I2STAT_M_TX_DAT_NACK));
return 1;
}
uint8_t digipot_mcp4451_send_byte(uint8_t data) {
LPC_I2C1->I2DAT = data & I2C_I2DAT_BITMASK; // transmit data
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
while (I2C_status != I2C_I2STAT_M_TX_DAT_ACK && I2C_status != I2C_I2STAT_M_TX_DAT_NACK); // wait for xmit to finish
return 1;
}
#ifdef __cplusplus
}
#endif
#endif // MB(MKS_SBASE)
#endif // TARGET_LPC1768

View File

@ -0,0 +1,43 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* digipot_mcp4451_I2C_routines.h
* Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
*/
#ifdef __cplusplus
extern "C" {
#endif
#include <lpc17xx_i2c.h>
#include <lpc17xx_pinsel.h>
#include <lpc17xx_libcfg_default.h>
#include "i2c_util.h"
uint8_t digipot_mcp4451_start(uint8_t sla);
uint8_t digipot_mcp4451_send_byte(uint8_t data);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,70 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
/**
* HAL_LPC1768/include/i2c_util.c
*/
#ifdef TARGET_LPC1768
#include "i2c_util.h"
#define U8G_I2C_OPT_FAST 16 // from u8g.h
#ifdef __cplusplus
extern "C" {
#endif
void configure_i2c(const uint8_t clock_option) {
/**
* Init I2C pin connect
*/
PINSEL_CFG_Type PinCfg;
PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
PinCfg.Portnum = 0;
#if I2C_MASTER_ID == 0
PinCfg.Funcnum = 1;
PinCfg.Pinnum = 27; // SDA0 / D57 AUX-1 ... SCL0 / D58 AUX-1
#elif I2C_MASTER_ID == 1
PinCfg.Funcnum = 3;
PinCfg.Pinnum = 0; // SDA1 / D20 SCA ... SCL1 / D21 SCL
#elif I2C_MASTER_ID == 2
PinCfg.Funcnum = 2;
PinCfg.Pinnum = 10; // SDA2 / D38 X_ENABLE_PIN ... SCL2 / D55 X_DIR_PIN
#endif
PINSEL_ConfigPin(&PinCfg);
PinCfg.Pinnum += 1;
PINSEL_ConfigPin(&PinCfg);
// Initialize I2C peripheral
I2C_Init(I2CDEV_M, (clock_option & U8G_I2C_OPT_FAST) ? 400000: 100000); // LCD data rates
// Enable Master I2C operation
I2C_Cmd(I2CDEV_M, I2C_MASTER_MODE, ENABLE);
}
#ifdef __cplusplus
}
#endif
#endif // TARGET_LPC1768

View File

@ -0,0 +1,56 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* HAL_LPC1768/include/i2c_util.h
*/
#include "../../../inc/MarlinConfigPre.h"
#ifndef I2C_MASTER_ID
#define I2C_MASTER_ID 1
#endif
#if I2C_MASTER_ID == 0
#define I2CDEV_M LPC_I2C0
#elif I2C_MASTER_ID == 1
#define I2CDEV_M LPC_I2C1
#elif I2C_MASTER_ID == 2
#define I2CDEV_M LPC_I2C2
#else
#error "Master I2C device not defined!"
#endif
#include <lpc17xx_i2c.h>
#include <lpc17xx_pinsel.h>
#include <lpc17xx_libcfg_default.h>
#ifdef __cplusplus
extern "C" {
#endif
void configure_i2c(const uint8_t clock_option);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,162 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 <usb/usb.h>
#include <usb/usbcfg.h>
#include <usb/usbhw.h>
#include <usb/usbcore.h>
#include <usb/cdc.h>
#include <usb/cdcuser.h>
#include <usb/mscuser.h>
#include <CDCSerial.h>
#include <usb/mscuser.h>
extern "C" {
#include <debug_frmwrk.h>
}
#include "../../sd/cardreader.h"
#include "../../inc/MarlinConfig.h"
#include "../../core/millis_t.h"
#include "HAL.h"
#include "timers.h"
extern uint32_t MSC_SD_Init(uint8_t pdrv);
extern "C" int isLPC1769();
extern "C" void disk_timerproc();
void SysTick_Callback() { disk_timerproc(); }
void HAL_init() {
// Init LEDs
#if PIN_EXISTS(LED)
SET_DIR_OUTPUT(LED_PIN);
WRITE_PIN_CLR(LED_PIN);
#if PIN_EXISTS(LED2)
SET_DIR_OUTPUT(LED2_PIN);
WRITE_PIN_CLR(LED2_PIN);
#if PIN_EXISTS(LED3)
SET_DIR_OUTPUT(LED3_PIN);
WRITE_PIN_CLR(LED3_PIN);
#if PIN_EXISTS(LED4)
SET_DIR_OUTPUT(LED4_PIN);
WRITE_PIN_CLR(LED4_PIN);
#endif
#endif
#endif
// 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
// Init Servo Pins
#define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
#if HAS_SERVO_0
INIT_SERVO(0);
#endif
#if HAS_SERVO_1
INIT_SERVO(1);
#endif
#if HAS_SERVO_2
INIT_SERVO(2);
#endif
#if HAS_SERVO_3
INIT_SERVO(3);
#endif
//debug_frmwrk_init();
//_DBG("\n\nDebug running\n");
// Initialise the SD card chip select pins as soon as possible
#if PIN_EXISTS(SS)
OUT_WRITE(SS_PIN, HIGH);
#endif
#if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SS_PIN
OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH);
#endif
#ifdef LPC1768_ENABLE_CLKOUT_12M
/**
* CLKOUTCFG register
* bit 8 (CLKOUT_EN) = enables CLKOUT signal. Disabled for now to prevent glitch when enabling GPIO.
* bits 7:4 (CLKOUTDIV) = set to 0 for divider setting of /1
* bits 3:0 (CLKOUTSEL) = set to 1 to select main crystal oscillator as CLKOUT source
*/
LPC_SC->CLKOUTCFG = (0<<8)|(0<<4)|(1<<0);
// set P1.27 pin to function 01 (CLKOUT)
PINSEL_CFG_Type PinCfg;
PinCfg.Portnum = 1;
PinCfg.Pinnum = 27;
PinCfg.Funcnum = 1; // function 01 (CLKOUT)
PinCfg.OpenDrain = 0; // not open drain
PinCfg.Pinmode = 2; // no pull-up/pull-down
PINSEL_ConfigPin(&PinCfg);
// now set CLKOUT_EN bit
LPC_SC->CLKOUTCFG |= (1<<8);
#endif
USB_Init(); // USB Initialization
USB_Connect(FALSE); // USB clear connection
delay(1000); // Give OS time to notice
USB_Connect(TRUE);
#if !BOTH(SHARED_SD_CARD, INIT_SDCARD_ON_BOOT) && DISABLED(NO_SD_HOST_DRIVE)
MSC_SD_Init(0); // Enable USB SD card access
#endif
const millis_t usb_timeout = millis() + 2000;
while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
delay(50);
HAL_idletask();
#if PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Flash quickly during USB initialization
#endif
}
HAL_timer_init();
}
// HAL idle task
void HAL_idletask() {
#if ENABLED(SHARED_SD_CARD)
// If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB.
// Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but
// this will not reliably detect delete operations. To be safe we will lock
// the disk if Marlin has it mounted. Unfortunately there is currently no way
// to unmount the disk from the LCD menu.
// if (IS_SD_PRINTING() || IS_SD_FILE_OPEN())
if (card.isMounted())
MSC_Aquire_Lock();
else
MSC_Release_Lock();
#endif
// Perform USB stack housekeeping
MSC_RunDeferredCommands();
}
#endif // TARGET_LPC1768

View File

@ -0,0 +1,26 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
#include "../shared/persistent_store_api.h"
#define FLASH_EEPROM_EMULATION

View File

@ -0,0 +1,129 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
/**
* Emulate EEPROM storage using Flash Memory
*
* Use a single 32K flash sector to store EEPROM data. To reduce the
* number of erase operations a simple "levelling" scheme is used that
* maintains a number of EEPROM "slots" within the larger flash sector.
* Each slot is used in turn and the entire sector is only erased when all
* slots have been used.
*
* A simple RAM image is used to hold the EEPROM data during I/O operations
* and this is flushed to the next available slot when an update is complete.
* If RAM usage becomes an issue we could store this image in one of the two
* 16Kb I/O buffers (intended to hold DMA USB and Ethernet data, but currently
* unused).
*/
#include "../../inc/MarlinConfigPre.h"
#if ENABLED(FLASH_EEPROM_EMULATION)
#include "persistent_store_api.h"
#include "../../inc/MarlinConfig.h"
extern "C" {
#include <lpc17xx_iap.h>
}
#define SECTOR_START(sector) ((sector < 16) ? (sector * 0x1000) : ((sector - 14) * 0x8000))
#define EEPROM_SECTOR 29
#define EEPROM_SIZE (4096)
#define SECTOR_SIZE (32768)
#define EEPROM_SLOTS (SECTOR_SIZE/EEPROM_SIZE)
#define EEPROM_ERASE (0xFF)
#define SLOT_ADDRESS(sector, slot) (((uint8_t *)SECTOR_START(sector)) + slot * EEPROM_SIZE)
static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0};
static bool eeprom_dirty = false;
static int current_slot = 0;
bool PersistentStore::access_start() {
uint32_t first_nblank_loc, first_nblank_val;
IAP_STATUS_CODE status;
// discover which slot we are currently using.
__disable_irq();
status = BlankCheckSector(EEPROM_SECTOR, EEPROM_SECTOR, &first_nblank_loc, &first_nblank_val);
__enable_irq();
if (status == CMD_SUCCESS) {
// sector is blank so nothing stored yet
for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = EEPROM_ERASE;
current_slot = EEPROM_SLOTS;
}
else {
// current slot is the first non blank one
current_slot = first_nblank_loc / EEPROM_SIZE;
uint8_t *eeprom_data = SLOT_ADDRESS(EEPROM_SECTOR, current_slot);
// load current settings
for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
}
eeprom_dirty = false;
return true;
}
bool PersistentStore::access_finish() {
if (eeprom_dirty) {
IAP_STATUS_CODE status;
if (--current_slot < 0) {
// all slots have been used, erase everything and start again
__disable_irq();
status = EraseSector(EEPROM_SECTOR, EEPROM_SECTOR);
__enable_irq();
current_slot = EEPROM_SLOTS - 1;
}
__disable_irq();
status = CopyRAM2Flash(SLOT_ADDRESS(EEPROM_SECTOR, current_slot), ram_eeprom, IAP_WRITE_4096);
__enable_irq();
if (status != CMD_SUCCESS) return false;
eeprom_dirty = false;
}
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (size_t i = 0; i < size; i++) ram_eeprom[pos + i] = value[i];
eeprom_dirty = true;
crc16(crc, value, size);
pos += size;
return false; // return true for any error
}
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos];
if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
crc16(crc, buff, size);
pos += size;
return false; // return true for any error
}
size_t PersistentStore::capacity() { return EEPROM_SIZE; }
#endif // FLASH_EEPROM_EMULATION
#endif // TARGET_LPC1768

View File

@ -0,0 +1,179 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.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 <http://www.gnu.org/licenses/>.
*
*/
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
#if ENABLED(SDCARD_EEPROM_EMULATION)
#include "persistent_store_api.h"
#include <chanfs/diskio.h>
#include <chanfs/ff.h>
extern uint32_t MSC_Aquire_Lock();
extern uint32_t MSC_Release_Lock();
FATFS fat_fs;
FIL eeprom_file;
bool eeprom_file_open = false;
bool PersistentStore::access_start() {
const char eeprom_erase_value = 0xFF;
MSC_Aquire_Lock();
if (f_mount(&fat_fs, "", 1)) {
MSC_Release_Lock();
return false;
}
FRESULT res = f_open(&eeprom_file, "eeprom.dat", FA_OPEN_ALWAYS | FA_WRITE | FA_READ);
if (res) MSC_Release_Lock();
if (res == FR_OK) {
UINT bytes_written;
FSIZE_t file_size = f_size(&eeprom_file);
f_lseek(&eeprom_file, file_size);
while (file_size < capacity() && res == FR_OK) {
res = f_write(&eeprom_file, &eeprom_erase_value, 1, &bytes_written);
file_size++;
}
}
if (res == FR_OK) {
f_lseek(&eeprom_file, 0);
f_sync(&eeprom_file);
eeprom_file_open = true;
}
return res == FR_OK;
}
bool PersistentStore::access_finish() {
f_close(&eeprom_file);
f_unmount("");
MSC_Release_Lock();
eeprom_file_open = false;
return true;
}
// This extra chit-chat goes away soon, but is helpful for now
// to see errors that are happening in read_data / write_data
static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) {
PGM_P const rw_str = write ? PSTR("write") : PSTR("read");
SERIAL_CHAR(' ');
serialprintPGM(rw_str);
SERIAL_ECHOPAIR("_data(", pos);
SERIAL_ECHOPAIR(",", (int)value);
SERIAL_ECHOPAIR(",", (int)size);
SERIAL_ECHOLNPGM(", ...)");
if (total) {
SERIAL_ECHOPGM(" f_");
serialprintPGM(rw_str);
SERIAL_ECHOPAIR("()=", (int)s);
SERIAL_ECHOPAIR("\n size=", size);
SERIAL_ECHOPGM("\n bytes_");
serialprintPGM(write ? PSTR("written=") : PSTR("read="));
SERIAL_ECHOLN(total);
}
else
SERIAL_ECHOLNPAIR(" f_lseek()=", (int)s);
}
// File function return codes for type FRESULT. This goes away soon, but
// is helpful right now to see any errors in read_data and write_data.
//
// typedef enum {
// FR_OK = 0, /* (0) Succeeded */
// FR_DISK_ERR, /* (1) A hard error occurred in the low level disk I/O layer */
// FR_INT_ERR, /* (2) Assertion failed */
// FR_NOT_READY, /* (3) The physical drive cannot work */
// FR_NO_FILE, /* (4) Could not find the file */
// FR_NO_PATH, /* (5) Could not find the path */
// FR_INVALID_NAME, /* (6) The path name format is invalid */
// FR_DENIED, /* (7) Access denied due to prohibited access or directory full */
// FR_EXIST, /* (8) Access denied due to prohibited access */
// FR_INVALID_OBJECT, /* (9) The file/directory object is invalid */
// FR_WRITE_PROTECTED, /* (10) The physical drive is write protected */
// FR_INVALID_DRIVE, /* (11) The logical drive number is invalid */
// FR_NOT_ENABLED, /* (12) The volume has no work area */
// FR_NO_FILESYSTEM, /* (13) There is no valid FAT volume */
// FR_MKFS_ABORTED, /* (14) The f_mkfs() aborted due to any problem */
// FR_TIMEOUT, /* (15) Could not get a grant to access the volume within defined period */
// FR_LOCKED, /* (16) The operation is rejected according to the file sharing policy */
// FR_NOT_ENOUGH_CORE, /* (17) LFN working buffer could not be allocated */
// FR_TOO_MANY_OPEN_FILES, /* (18) Number of open files > FF_FS_LOCK */
// FR_INVALID_PARAMETER /* (19) Given parameter is invalid */
// } FRESULT;
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
if (!eeprom_file_open) return true;
FRESULT s;
UINT bytes_written = 0;
s = f_lseek(&eeprom_file, pos);
if (s) {
debug_rw(true, pos, value, size, s);
return s;
}
s = f_write(&eeprom_file, (void*)value, size, &bytes_written);
if (s) {
debug_rw(true, pos, value, size, s, bytes_written);
return s;
}
crc16(crc, value, size);
pos += size;
return bytes_written != size; // return true for any error
}
bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) {
if (!eeprom_file_open) return true;
UINT bytes_read = 0;
FRESULT s;
s = f_lseek(&eeprom_file, pos);
if (s) {
debug_rw(false, pos, value, size, s);
return true;
}
if (writing) {
s = f_read(&eeprom_file, (void*)value, size, &bytes_read);
crc16(crc, value, size);
}
else {
uint8_t temp[size];
s = f_read(&eeprom_file, (void*)temp, size, &bytes_read);
crc16(crc, temp, size);
}
if (s) {
debug_rw(false, pos, value, size, s, bytes_read);
return true;
}
pos += size;
return bytes_read != size; // return true for any error
}
size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM
#endif // SDCARD_EEPROM_EMULATION
#endif // TARGET_LPC1768

View File

@ -0,0 +1,53 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Support routines for LPC1768
*/
/**
* Translation of routines & variables used by pinsDebug.h
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define pwm_details(pin) pin = pin // do nothing // print PWM details
#define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin.
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PORT(p)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%d.%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
#ifndef M43_NEVER_TOUCH
#define M43_NEVER_TOUCH(Q) ((Q) == P0_29 || (Q) == P0_30 || (Q) == P2_09) // USB pins
#endif
bool GET_PINMODE(const pin_t pin) {
if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // found an invalid pin or active analog pin
return false;
return LPC176x::gpio_direction(pin);
}
bool GET_ARRAY_IS_DIGITAL(const pin_t pin) {
return (!LPC176x::pin_has_adc(pin) || !LPC176x::pin_adc_enabled(pin));
}

View File

@ -0,0 +1,54 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
#include "../../core/macros.h"
#if ENABLED(SDSUPPORT) && HAS_GRAPHICAL_LCD && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
#define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently
// needed due to the speed and mode required for communicating with each device being different.
// This requirement can be removed if the SPI access to these devices is updated to use
// spiBeginTransaction.
#endif
/** onboard SD card */
//#define SCK_PIN P0_07
//#define MISO_PIN P0_08
//#define MOSI_PIN P0_09
//#define SS_PIN P0_06
/** external */
#ifndef SCK_PIN
#define SCK_PIN P0_15
#endif
#ifndef MISO_PIN
#define MISO_PIN P0_17
#endif
#ifndef MOSI_PIN
#define MOSI_PIN P0_18
#endif
#ifndef SS_PIN
#define SS_PIN P1_23
#endif
#if !defined(SDSS) || SDSS == P_NC // gets defaulted in pins.h
#undef SDSS
#define SDSS SS_PIN
#endif

View File

@ -0,0 +1,66 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Description:
*
* Timers for LPC1768
*/
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
#include "timers.h"
void HAL_timer_init() {
SBI(LPC_SC->PCONP, SBIT_TIMER0); // Power ON Timer 0
LPC_TIM0->PR = (HAL_TIMER_RATE) / (STEPPER_TIMER_RATE) - 1; // Use prescaler to set frequency if needed
SBI(LPC_SC->PCONP, SBIT_TIMER1); // Power ON Timer 1
LPC_TIM1->PR = (HAL_TIMER_RATE) / 1000000 - 1;
}
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
switch (timer_num) {
case 0:
LPC_TIM0->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them
LPC_TIM0->MR0 = uint32_t(STEPPER_TIMER_RATE) / frequency; // Match value (period) to set frequency
LPC_TIM0->TCR = _BV(SBIT_CNTEN); // Counter Enable
NVIC_SetPriority(TIMER0_IRQn, NVIC_EncodePriority(0, 1, 0));
NVIC_EnableIRQ(TIMER0_IRQn);
break;
case 1:
LPC_TIM1->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them
LPC_TIM1->MR0 = uint32_t(TEMP_TIMER_RATE) / frequency;
LPC_TIM1->TCR = _BV(SBIT_CNTEN); // Counter Enable
NVIC_SetPriority(TIMER1_IRQn, NVIC_EncodePriority(0, 2, 0));
NVIC_EnableIRQ(TIMER1_IRQn);
break;
default: break;
}
}
#endif // TARGET_LPC1768

View File

@ -0,0 +1,162 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 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 <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
*
* HAL For LPC1768
*/
#include <stdint.h>
#include "../../core/macros.h"
#define SBIT_TIMER0 1
#define SBIT_TIMER1 2
#define SBIT_CNTEN 0
#define SBIT_MR0I 0 // Timer 0 Interrupt when TC matches MR0
#define SBIT_MR0R 1 // Timer 0 Reset TC on Match
#define SBIT_MR0S 2 // Timer 0 Stop TC and PC on Match
#define SBIT_MR1I 3
#define SBIT_MR1R 4
#define SBIT_MR1S 5
#define SBIT_MR2I 6
#define SBIT_MR2R 7
#define SBIT_MR2S 8
#define SBIT_MR3I 9
#define SBIT_MR3R 10
#define SBIT_MR3S 11
// ------------------------
// Defines
// ------------------------
#define _HAL_TIMER(T) _CAT(LPC_TIM, T)
#define _HAL_TIMER_IRQ(T) TIMER##T##_IRQn
#define __HAL_TIMER_ISR(T) extern "C" void TIMER##T##_IRQHandler()
#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#define PWM_TIMER_NUM 3 // Timer Index for PWM
#define TEMP_TIMER_RATE 1000000
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#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 STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(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_STEP_TIMER_ISR() _HAL_TIMER_ISR(STEP_TIMER_NUM)
#define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM)
// Timer references by index
#define STEP_TIMER _HAL_TIMER(STEP_TIMER_NUM)
#define TEMP_TIMER _HAL_TIMER(TEMP_TIMER_NUM)
// ------------------------
// Public functions
// ------------------------
void HAL_timer_init();
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
switch (timer_num) {
case 0: STEP_TIMER->MR0 = compare; break; // Stepper Timer Match Register 0
case 1: TEMP_TIMER->MR0 = compare; break; // Temp Timer Match Register 0
}
}
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
switch (timer_num) {
case 0: return STEP_TIMER->MR0; // Stepper Timer Match Register 0
case 1: return TEMP_TIMER->MR0; // Temp Timer Match Register 0
}
return 0;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
switch (timer_num) {
case 0: return STEP_TIMER->TC; // Stepper Timer Count
case 1: return TEMP_TIMER->TC; // Temp Timer Count
}
return 0;
}
FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) {
switch (timer_num) {
case 0: NVIC_EnableIRQ(TIMER0_IRQn); break; // Enable interrupt handler
case 1: NVIC_EnableIRQ(TIMER1_IRQn); break; // Enable interrupt handler
}
}
FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) {
switch (timer_num) {
case 0: NVIC_DisableIRQ(TIMER0_IRQn); break; // Disable interrupt handler
case 1: NVIC_DisableIRQ(TIMER1_IRQn); break; // Disable interrupt handler
}
// 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();
}
// This function is missing from CMSIS
FORCE_INLINE static bool NVIC_GetEnableIRQ(IRQn_Type IRQn) {
return (NVIC->ISER[((uint32_t)IRQn) >> 5] & (1 << ((uint32_t)IRQn) & 0x1F)) != 0;
}
FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
switch (timer_num) {
case 0: return NVIC_GetEnableIRQ(TIMER0_IRQn); // Check if interrupt is enabled or not
case 1: return NVIC_GetEnableIRQ(TIMER1_IRQn); // Check if interrupt is enabled or not
}
return false;
}
FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
switch (timer_num) {
case 0: SBI(STEP_TIMER->IR, SBIT_CNTEN); break;
case 1: SBI(TEMP_TIMER->IR, SBIT_CNTEN); break;
}
}
#define HAL_timer_isr_epilogue(TIMER_NUM)

View File

@ -0,0 +1,123 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef TARGET_LPC1768
#include "../include/i2c_util.h"
#include "../../../core/millis_t.h"
extern int millis();
#ifdef __cplusplus
extern "C" {
#endif
//////////////////////////////////////////////////////////////////////////////////////
// These two routines are exact copies of the lpc17xx_i2c.c routines. Couldn't link to
// to the lpc17xx_i2c.c routines so had to copy them into this file & rename them.
static uint32_t _I2C_Start(LPC_I2C_TypeDef *I2Cx) {
// Reset STA, STO, SI
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC|I2C_I2CONCLR_STOC|I2C_I2CONCLR_STAC;
// Enter to Master Transmitter mode
I2Cx->I2CONSET = I2C_I2CONSET_STA;
// Wait for complete
while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
}
static void _I2C_Stop (LPC_I2C_TypeDef *I2Cx) {
/* Make sure start bit is not active */
if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
I2Cx->I2CONSET = I2C_I2CONSET_STO|I2C_I2CONSET_AA;
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
}
//////////////////////////////////////////////////////////////////////////////////////
#define I2CDEV_S_ADDR 0x78 // from SSD1306 //actual address is 0x3C - shift left 1 with LSB set to 0 to indicate write
#define BUFFER_SIZE 0x1 // only do single byte transfers with LCDs
I2C_M_SETUP_Type transferMCfg;
#define I2C_status (LPC_I2C1->I2STAT & I2C_STAT_CODE_BITMASK)
// Send slave address and write bit
uint8_t u8g_i2c_start(const uint8_t sla) {
// Sometimes TX data ACK or NAK status is returned. That mean the start state didn't
// happen which means only the value of the slave address was send. Keep looping until
// the slave address and write bit are actually sent.
do{
_I2C_Stop(I2CDEV_M); // output stop state on I2C bus
_I2C_Start(I2CDEV_M); // output start state on I2C bus
while ((I2C_status != I2C_I2STAT_M_TX_START)
&& (I2C_status != I2C_I2STAT_M_TX_RESTART)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_NACK)); //wait for start to be asserted
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_STAC; // clear start state before tansmitting slave address
LPC_I2C1->I2DAT = I2CDEV_S_ADDR & I2C_I2DAT_BITMASK; // transmit slave address & write bit
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
while ((I2C_status != I2C_I2STAT_M_TX_SLAW_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_SLAW_NACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_NACK)); //wait for slaw to finish
}while ( (I2C_status == I2C_I2STAT_M_TX_DAT_ACK) || (I2C_status == I2C_I2STAT_M_TX_DAT_NACK));
return 1;
}
void u8g_i2c_init(const uint8_t clock_option) {
configure_i2c(clock_option);
u8g_i2c_start(0); // Send slave address and write bit
}
uint8_t u8g_i2c_send_byte(uint8_t data) {
#define I2C_TIMEOUT 3
LPC_I2C1->I2DAT = data & I2C_I2DAT_BITMASK; // transmit data
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
const millis_t timeout = millis() + I2C_TIMEOUT;
while ((I2C_status != I2C_I2STAT_M_TX_DAT_ACK) && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK) && PENDING(millis(), timeout)); // wait for xmit to finish
// had hangs with SH1106 so added time out - have seen temporary screen corruption when this happens
return 1;
}
void u8g_i2c_stop() {
}
#ifdef __cplusplus
}
#endif
#endif // TARGET_LPC1768

View File

@ -0,0 +1,28 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
void u8g_i2c_init(const uint8_t clock_options);
//uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos);
uint8_t u8g_i2c_start(uint8_t sla);
uint8_t u8g_i2c_send_byte(uint8_t data);
void u8g_i2c_stop();

View File

@ -0,0 +1,49 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* LPC1768 LCD-specific defines
*/
// The following are optional depending on the platform.
// definitions of HAL specific com and device drivers.
uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
// connect U8g com generic com names to the desired driver
#define U8G_COM_HW_SPI u8g_com_HAL_LPC1768_hw_spi_fn // use LPC1768 specific hardware SPI routine
#define U8G_COM_SW_SPI u8g_com_HAL_LPC1768_sw_spi_fn // use LPC1768 specific software SPI routine
#define U8G_COM_ST7920_HW_SPI u8g_com_HAL_LPC1768_ST7920_hw_spi_fn
#define U8G_COM_ST7920_SW_SPI u8g_com_HAL_LPC1768_ST7920_sw_spi_fn
#define U8G_COM_SSD_I2C u8g_com_HAL_LPC1768_ssd_hw_i2c_fn
// let these default for now
#define U8G_COM_PARALLEL u8g_com_null_fn
#define U8G_COM_T6963 u8g_com_null_fn
#define U8G_COM_FAST_PARALLEL u8g_com_null_fn
#define U8G_COM_UC_I2C u8g_com_null_fn

View File

@ -0,0 +1,43 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* LCD delay routines - used by all the drivers.
*
* These are based on the LPC1768 routines.
*
* Couldn't just call exact copies because the overhead
* results in a one microsecond delay taking about 4µS.
*/
#ifdef __cplusplus
extern "C" {
#endif
void U8g_delay(int msec);
void u8g_MicroDelay();
void u8g_10MicroDelay();
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,110 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
/**
* Low level pin manipulation routines - used by all the drivers.
*
* These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines.
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
*/
#ifdef TARGET_LPC1768
#include <LPC17xx.h>
#include <lpc17xx_pinsel.h>
#include "../../../core/macros.h"
//#include <pinmapping.h>
#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 INPUT 0
#define OUTPUT 1
#define INPUT_PULLUP 2
uint8_t LPC1768_PIN_PORT(const uint8_t pin);
uint8_t LPC1768_PIN_PIN(const uint8_t pin);
#ifdef __cplusplus
extern "C" {
#endif
// I/O functions
// As defined by Arduino INPUT(0x0), OUTPUT(0x1), INPUT_PULLUP(0x2)
void pinMode_LCD(uint8_t pin, uint8_t mode) {
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
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));
PINSEL_ConfigPin(&config);
break;
case OUTPUT:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin));
PINSEL_ConfigPin(&config);
break;
case INPUT_PULLUP:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
config.Pinmode = PINSEL_PINMODE_PULLUP;
PINSEL_ConfigPin(&config);
break;
default: break;
}
}
void u8g_SetPinOutput(uint8_t internal_pin_number) {
pinMode_LCD(internal_pin_number, 1); // OUTPUT
}
void u8g_SetPinInput(uint8_t internal_pin_number) {
pinMode_LCD(internal_pin_number, 0); // INPUT
}
void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status) {
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
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));
}
uint8_t u8g_GetPinLevel(uint8_t pin) {
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
return (uint32_t)LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
}
#ifdef __cplusplus
}
#endif
#endif // TARGET_LPC1768

View File

@ -0,0 +1,37 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
/**
* Low level pin manipulation routines - used by all the drivers.
*
* These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines.
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
*/
void u8g_SetPinOutput(uint8_t internal_pin_number);
void u8g_SetPinInput(uint8_t internal_pin_number);
void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status);
uint8_t u8g_GetPinLevel(uint8_t pin);

View File

@ -0,0 +1,129 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 u8g_com_msp430_hw_spi.c
*
* Universal 8bit Graphics Library
*
* Copyright (c) 2011, olikraus@gmail.com
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or other
* materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfigPre.h"
#if HAS_GRAPHICAL_LCD
#include <U8glib.h>
#include "../../shared/HAL_SPI.h"
void spiBegin();
void spiInit(uint8_t spiRate);
void spiSend(uint8_t b);
void spiSend(const uint8_t* buf, size_t n);
uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
switch (msg) {
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_INIT:
u8g_SetPILevel(u8g, U8G_PI_CS, 1);
u8g_SetPILevel(u8g, U8G_PI_A0, 1);
u8g_SetPILevel(u8g, U8G_PI_RESET, 1);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_SetPIOutput(u8g, U8G_PI_A0);
u8g_SetPIOutput(u8g, U8G_PI_RESET);
u8g_Delay(5);
spiBegin();
#ifndef SPI_SPEED
#define SPI_SPEED SPI_FULL_SPEED // use same SPI speed as SD card
#endif
spiInit(SPI_SPEED);
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g_SetPILevel(u8g, U8G_PI_A0, arg_val);
break;
case U8G_COM_MSG_CHIP_SELECT:
u8g_SetPILevel(u8g, U8G_PI_CS, (arg_val ? 0 : 1));
break;
case U8G_COM_MSG_RESET:
u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_WRITE_BYTE:
spiSend((uint8_t)arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t *ptr = (uint8_t*) arg_ptr;
while (arg_val > 0) {
spiSend(*ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P: {
uint8_t *ptr = (uint8_t*) arg_ptr;
while (arg_val > 0) {
spiSend(*ptr++);
arg_val--;
}
}
break;
}
return 1;
}
#endif // HAS_GRAPHICAL_LCD
#endif // TARGET_LPC1768

View File

@ -0,0 +1,198 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 u8g_com_arduino_ssd_i2c.c
*
* COM interface for Arduino (AND ATmega) and the SSDxxxx chip (SOLOMON) variant
* I2C protocol
*
* Universal 8bit Graphics Library
*
* Copyright (c) 2011, olikraus@gmail.com
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or other
* materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* Special pin usage:
* U8G_PI_I2C_OPTION additional options
* U8G_PI_A0_STATE used to store the last value of the command/data register selection
* U8G_PI_SET_A0 1: Signal request to update I2C device with new A0_STATE, 0: Do nothing, A0_STATE matches I2C device
* U8G_PI_SCL clock line (NOT USED)
* U8G_PI_SDA data line (NOT USED)
*
* U8G_PI_RESET reset line (currently disabled, see below)
*
* Protocol:
* SLA, Cmd/Data Selection, Arguments
* The command/data register is selected by a special instruction byte, which is sent after SLA
*
* The continue bit is always 0 so that a (re)start is equired for the change from cmd to/data mode
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfigPre.h"
#if HAS_GRAPHICAL_LCD
#include <U8glib.h>
#define I2C_SLA (0x3C*2)
//#define I2C_CMD_MODE 0x080
#define I2C_CMD_MODE 0x000
#define I2C_DATA_MODE 0x040
uint8_t u8g_com_ssd_I2C_start_sequence(u8g_t *u8g) {
/* are we requested to set the a0 state? */
if (u8g->pin_list[U8G_PI_SET_A0] == 0) return 1;
/* setup bus, might be a repeated start */
if (u8g_i2c_start(I2C_SLA) == 0) return 0;
if (u8g->pin_list[U8G_PI_A0_STATE] == 0) {
if (u8g_i2c_send_byte(I2C_CMD_MODE) == 0) return 0;
}
else if (u8g_i2c_send_byte(I2C_DATA_MODE) == 0)
return 0;
u8g->pin_list[U8G_PI_SET_A0] = 0;
return 1;
}
uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
switch (msg) {
case U8G_COM_MSG_INIT:
//u8g_com_arduino_digital_write(u8g, U8G_PI_SCL, HIGH);
//u8g_com_arduino_digital_write(u8g, U8G_PI_SDA, HIGH);
//u8g->pin_list[U8G_PI_A0_STATE] = 0; /* initial RS state: unknown mode */
u8g_i2c_init(u8g->pin_list[U8G_PI_I2C_OPTION]);
u8g_com_ssd_I2C_start_sequence(u8g);
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
/* Currently disabled, but it could be enable. Previous restrictions have been removed */
/* u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); */
break;
case U8G_COM_MSG_CHIP_SELECT:
u8g->pin_list[U8G_PI_A0_STATE] = 0;
u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again, also forces start condition */
if (arg_val == 0 ) {
/* disable chip, send stop condition */
u8g_i2c_stop();
}
else {
/* enable, do nothing: any byte writing will trigger the i2c start */
}
break;
case U8G_COM_MSG_WRITE_BYTE:
//u8g->pin_list[U8G_PI_SET_A0] = 1;
if (u8g_com_ssd_I2C_start_sequence(u8g) == 0) {
u8g_i2c_stop();
return 0;
}
if (u8g_i2c_send_byte(arg_val) == 0) {
u8g_i2c_stop();
return 0;
}
// u8g_i2c_stop();
break;
case U8G_COM_MSG_WRITE_SEQ: {
//u8g->pin_list[U8G_PI_SET_A0] = 1;
if (u8g_com_ssd_I2C_start_sequence(u8g) == 0) {
u8g_i2c_stop();
return 0;
}
uint8_t *ptr = (uint8_t *)arg_ptr;
while (arg_val > 0) {
if (u8g_i2c_send_byte(*ptr++) == 0) {
u8g_i2c_stop();
return 0;
}
arg_val--;
}
}
// u8g_i2c_stop();
break;
case U8G_COM_MSG_WRITE_SEQ_P: {
//u8g->pin_list[U8G_PI_SET_A0] = 1;
if (u8g_com_ssd_I2C_start_sequence(u8g) == 0) {
u8g_i2c_stop();
return 0;
}
uint8_t *ptr = (uint8_t *)arg_ptr;
while (arg_val > 0) {
if (u8g_i2c_send_byte(u8g_pgm_read(ptr)) == 0)
return 0;
ptr++;
arg_val--;
}
}
// u8g_i2c_stop();
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again */
break;
} // switch
return 1;
}
#endif // HAS_GRAPHICAL_LCD
#endif // TARGET_LPC1768

View File

@ -0,0 +1,138 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 u8g_com_LPC1768_st7920_hw_spi.c
*
* Universal 8bit Graphics Library
*
* Copyright (c) 2011, olikraus@gmail.com
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or other
* materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfigPre.h"
#if HAS_GRAPHICAL_LCD
#include <U8glib.h>
#include "../../shared/HAL_SPI.h"
#include "../../shared/Delay.h"
void spiBegin();
void spiInit(uint8_t spiRate);
void spiSend(uint8_t b);
void spiSend(const uint8_t* buf, size_t n);
static uint8_t rs_last_state = 255;
static void u8g_com_LPC1768_st7920_write_byte_hw_spi(uint8_t rs, uint8_t val) {
if (rs != rs_last_state) { // Time to send a command/data byte
rs_last_state = rs;
spiSend(rs ? 0x0FA : 0x0F8); // Send data or command
DELAY_US(40); // Give the controller some time: 20 is bad, 30 is OK, 40 is safe
}
spiSend(val & 0xF0);
spiSend(val << 4);
}
uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
switch (msg) {
case U8G_COM_MSG_INIT:
u8g_SetPILevel(u8g, U8G_PI_CS, 0);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_Delay(5);
spiBegin();
spiInit(SPI_EIGHTH_SPEED); // ST7920 max speed is about 1.1 MHz
u8g->pin_list[U8G_PI_A0_STATE] = 0; // initial RS state: command mode
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1)
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
break;
case U8G_COM_MSG_CHIP_SELECT:
u8g_SetPILevel(u8g, U8G_PI_CS, arg_val); // Note: the ST7920 has an active high chip-select
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_com_LPC1768_st7920_write_byte_hw_spi(u8g->pin_list[U8G_PI_A0_STATE], arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t *ptr = (uint8_t*) arg_ptr;
while (arg_val > 0) {
u8g_com_LPC1768_st7920_write_byte_hw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P: {
uint8_t *ptr = (uint8_t*) arg_ptr;
while (arg_val > 0) {
u8g_com_LPC1768_st7920_write_byte_hw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
}
return 1;
}
#endif // HAS_GRAPHICAL_LCD
#endif // TARGET_LPC1768

View File

@ -0,0 +1,145 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 u8g_com_st7920_hw_spi.c
*
* Universal 8bit Graphics Library
*
* Copyright (c) 2011, olikraus@gmail.com
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or other
* materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfigPre.h"
#if ENABLED(U8GLIB_ST7920)
#include <U8glib.h>
#include <SoftwareSPI.h>
#include "../../shared/Delay.h"
#undef SPI_SPEED
#define SPI_SPEED 3 // About 1 MHz
static pin_t SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL;
static uint8_t SPI_speed = 0;
static void u8g_com_LPC1768_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) {
static uint8_t rs_last_state = 255;
if (rs != rs_last_state) {
// Transfer Data (FA) or Command (F8)
swSpiTransfer(rs ? 0x0FA : 0x0F8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
rs_last_state = rs;
DELAY_US(40); // Give the controller time to process the data: 20 is bad, 30 is OK, 40 is safe
}
swSpiTransfer(val & 0x0F0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
swSpiTransfer(val << 4, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
}
uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
switch (msg) {
case U8G_COM_MSG_INIT:
SCK_pin_ST7920_HAL = u8g->pin_list[U8G_PI_SCK];
MOSI_pin_ST7920_HAL_HAL = u8g->pin_list[U8G_PI_MOSI];
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_SetPIOutput(u8g, U8G_PI_SCK);
u8g_SetPIOutput(u8g, U8G_PI_MOSI);
u8g_Delay(5);
SPI_speed = swSpiInit(SPI_SPEED, SCK_pin_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL);
u8g_SetPILevel(u8g, U8G_PI_CS, 0);
u8g_SetPILevel(u8g, U8G_PI_SCK, 0);
u8g_SetPILevel(u8g, U8G_PI_MOSI, 0);
u8g->pin_list[U8G_PI_A0_STATE] = 0; /* initial RS state: command mode */
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
break;
case U8G_COM_MSG_CHIP_SELECT:
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_CS]) u8g_SetPILevel(u8g, U8G_PI_CS, arg_val); //note: the st7920 has an active high chip select
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_com_LPC1768_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t *ptr = (uint8_t*) arg_ptr;
while (arg_val > 0) {
u8g_com_LPC1768_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P: {
uint8_t *ptr = (uint8_t*) arg_ptr;
while (arg_val > 0) {
u8g_com_LPC1768_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
}
return 1;
}
#endif // U8GLIB_ST7920
#endif // TARGET_LPC1768

View File

@ -0,0 +1,207 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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 u8g_com_std_sw_spi.c
*
* Universal 8bit Graphics Library
*
* Copyright (c) 2015, olikraus@gmail.com
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or other
* materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfigPre.h"
#if HAS_GRAPHICAL_LCD && DISABLED(U8GLIB_ST7920)
#include <SoftwareSPI.h>
#undef SPI_SPEED
#define SPI_SPEED 2 // About 2 MHz
#include <Arduino.h>
#include <algorithm>
#include <LPC17xx.h>
#include <gpio.h>
#include <U8glib.h>
uint8_t swSpiTransfer_mode_0(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) {
LPC176x::gpio_set(mosi_pin, !!(b & 0x80));
LPC176x::gpio_set(sck_pin, HIGH);
b <<= 1;
if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1;
LPC176x::gpio_set(sck_pin, LOW);
}
else {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
for (uint8_t j = 0; j < spi_speed; j++)
LPC176x::gpio_set(mosi_pin, state);
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
LPC176x::gpio_set(sck_pin, HIGH);
b <<= 1;
if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1;
for (uint8_t j = 0; j < spi_speed; j++)
LPC176x::gpio_set(sck_pin, LOW);
}
}
return b;
}
uint8_t swSpiTransfer_mode_3(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++) {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
if (spi_speed == 0) {
LPC176x::gpio_set(sck_pin, LOW);
LPC176x::gpio_set(mosi_pin, state);
LPC176x::gpio_set(mosi_pin, state); // need some setup time
LPC176x::gpio_set(sck_pin, HIGH);
}
else {
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
LPC176x::gpio_set(sck_pin, LOW);
for (uint8_t j = 0; j < spi_speed; j++)
LPC176x::gpio_set(mosi_pin, state);
for (uint8_t j = 0; j < spi_speed; j++)
LPC176x::gpio_set(sck_pin, HIGH);
}
b <<= 1;
if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1;
}
return b;
}
static uint8_t SPI_speed = 0;
static void u8g_sw_spi_HAL_LPC1768_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) {
#if EITHER(FYSETC_MINI_12864, MKS_MINI_12864)
swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin);
#else
swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin);
#endif
}
uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
switch (msg) {
case U8G_COM_MSG_INIT:
u8g_SetPIOutput(u8g, U8G_PI_SCK);
u8g_SetPIOutput(u8g, U8G_PI_MOSI);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_SetPIOutput(u8g, U8G_PI_A0);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPIOutput(u8g, U8G_PI_RESET);
SPI_speed = swSpiInit(SPI_SPEED, u8g->pin_list[U8G_PI_SCK], u8g->pin_list[U8G_PI_MOSI]);
u8g_SetPILevel(u8g, U8G_PI_SCK, 0);
u8g_SetPILevel(u8g, U8G_PI_MOSI, 0);
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_CHIP_SELECT:
#if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0
if (arg_val) { // SCK idle state needs to be set to the proper idle state before
// the next chip select goes active
u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active
u8g_SetPILevel(u8g, U8G_PI_CS, LOW);
}
else {
u8g_SetPILevel(u8g, U8G_PI_CS, HIGH);
u8g_SetPILevel(u8g, U8G_PI_SCK, 0); // Set SCK to mode 0 idle state after CS goes inactive
}
#else
u8g_SetPILevel(u8g, U8G_PI_CS, !arg_val);
#endif
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t *ptr = (uint8_t *)arg_ptr;
while (arg_val > 0) {
u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P: {
uint8_t *ptr = (uint8_t *)arg_ptr;
while (arg_val > 0) {
u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr));
ptr++;
arg_val--;
}
}
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g_SetPILevel(u8g, U8G_PI_A0, arg_val);
break;
}
return 1;
}
#endif // HAS_GRAPHICAL_LCD && !U8GLIB_ST7920
#endif // TARGET_LPC1768

View File

@ -0,0 +1,145 @@
#
# sets output_port
# if target_filename is found then that drive is used
# else if target_drive is found then that drive is used
#
from __future__ import print_function
target_filename = "FIRMWARE.CUR"
target_drive = "REARM"
import os
import getpass
import platform
current_OS = platform.system()
Import("env")
def print_error(e):
print('\nUnable to find destination disk (%s)\n' \
'Please select it in platformio.ini using the upload_port keyword ' \
'(https://docs.platformio.org/en/latest/projectconf/section_env_upload.html) ' \
'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \
%(e, env.get('PIOENV')))
try:
if current_OS == 'Windows':
#
# platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:'
# Windows - doesn't care about the disk's name, only cares about the drive letter
#
#
# get all drives on this computer
#
import subprocess
# typical result (string): 'Drives: C:\ D:\ E:\ F:\ G:\ H:\ I:\ J:\ K:\ L:\ M:\ Y:\ Z:\'
driveStr = str(subprocess.check_output("fsutil fsinfo drives"))
# typical result (string): 'C:\ D:\ E:\ F:\ G:\ H:\ I:\ J:\ K:\ L:\ M:\ Y:\ Z:\'
# driveStr = driveStr.strip().lstrip('Drives: ') <- Doesn't work in other Languages as English. In German is "Drives:" = "Laufwerke:"
FirstFound = driveStr.find(':',0,-1) # Find the first ":" and
driveStr = driveStr[FirstFound + 1 : -1] # truncate to the rest
# typical result (array of stings): ['C:\\', 'D:\\', 'E:\\', 'F:\\',
# 'G:\\', 'H:\\', 'I:\\', 'J:\\', 'K:\\', 'L:\\', 'M:\\', 'Y:\\', 'Z:\\']
drives = driveStr.split()
upload_disk = 'Disk not found'
target_file_found = False
target_drive_found = False
for drive in drives:
final_drive_name = drive.strip().rstrip('\\') # typical result (string): 'C:'
try:
volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT))
except Exception as e:
continue
else:
if target_drive in volume_info and target_file_found == False: # set upload if not found target file yet
target_drive_found = True
upload_disk = final_drive_name
if target_filename in volume_info:
if target_file_found == False:
upload_disk = final_drive_name
target_file_found = True
#
# set upload_port to drive if found
#
if target_file_found == True or target_drive_found == True:
env.Replace(
UPLOAD_PORT=upload_disk
)
print('upload disk: ', upload_disk)
else:
print_error('Autodetect Error')
elif current_OS == 'Linux':
#
# platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive'
#
upload_disk = 'Disk not found'
target_file_found = False
target_drive_found = False
drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser()))
if target_drive in drives: # If target drive is found, use it.
target_drive_found = True
upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep
else:
for drive in drives:
try:
files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive))
except:
continue
else:
if target_filename in files:
upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep
target_file_found = True
break
#
# set upload_port to drive if found
#
if target_file_found or target_drive_found:
env.Replace(
UPLOAD_FLAGS="-P$UPLOAD_PORT",
UPLOAD_PORT=upload_disk
)
print('upload disk: ', upload_disk)
else:
print_error('Autodetect Error')
elif current_OS == 'Darwin': # MAC
#
# platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive'
#
upload_disk = 'Disk not found'
drives = os.listdir('/Volumes') # human readable names
target_file_found = False
target_drive_found = False
if target_drive in drives and target_file_found == False: # set upload if not found target file yet
target_drive_found = True
upload_disk = '/Volumes/' + target_drive + '/'
for drive in drives:
try:
filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected
except:
continue
else:
if target_filename in filenames:
if target_file_found == False:
upload_disk = '/Volumes/' + drive + '/'
target_file_found = True
#
# set upload_port to drive if found
#
if target_file_found == True or target_drive_found == True:
env.Replace(
UPLOAD_PORT=upload_disk
)
print('\nupload disk: ', upload_disk, '\n')
else:
print_error('Autodetect Error')
except Exception as e:
print_error(str(e))

View File

@ -0,0 +1,37 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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"
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/e_parser.h"
EmergencyParser::State emergency_state;
bool CDC_RecvCallback(const char buffer) {
emergency_parser.update(emergency_state, buffer);
return true;
}
#endif // EMERGENCY_PARSER
#endif // TARGET_LPC1768

View File

@ -0,0 +1,71 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG)
#include <lpc17xx_wdt.h>
#include "watchdog.h"
void watchdog_init() {
#if ENABLED(WATCHDOG_RESET_MANUAL)
// We enable the watchdog timer, but only for the interrupt.
// Configure WDT to only trigger an interrupt
// Disable WDT interrupt (just in case, to avoid triggering it!)
NVIC_DisableIRQ(WDT_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();
// Configure WDT to only trigger an interrupt
// Initialize WDT with the given parameters
WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_INT_ONLY);
// Configure and enable WDT interrupt.
NVIC_ClearPendingIRQ(WDT_IRQn);
NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups
NVIC_EnableIRQ(WDT_IRQn);
#else
WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET);
#endif
WDT_Start(WDT_TIMEOUT);
}
void HAL_watchdog_refresh() {
WDT_Feed();
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // heartbeat indicator
#endif
}
// Timeout state
bool watchdog_timed_out() { return TEST(WDT_ReadTimeOutFlag(), 0); }
void watchdog_clear_timeout_flag() { WDT_ClrTimeOutFlag(); }
#endif // USE_WATCHDOG
#endif // TARGET_LPC1768

View File

@ -0,0 +1,30 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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/>.
*
*/
#pragma once
#define WDT_TIMEOUT 4000000 // 4 second timeout
void watchdog_init();
void HAL_watchdog_refresh();
bool watchdog_timed_out();
void watchdog_clear_timeout_flag();

View File

@ -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"