LPC176x Framework update (#15722)
Changes required for compatibility with framework-arduino-lpc176x 0.2.0
This commit is contained in:
parent
15f94e5ee5
commit
b9116d4050
@ -30,6 +30,8 @@
|
|||||||
#include "watchdog.h"
|
#include "watchdog.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
uint32_t HAL_adc_reading = 0;
|
||||||
|
|
||||||
// U8glib required functions
|
// U8glib required functions
|
||||||
extern "C" void u8g_xMicroDelay(uint16_t val) {
|
extern "C" void u8g_xMicroDelay(uint16_t val) {
|
||||||
DELAY_US(val);
|
DELAY_US(val);
|
||||||
@ -61,7 +63,7 @@ int freeMemory() {
|
|||||||
// return dval if not found or not a valid pin.
|
// return dval if not found or not a valid pin.
|
||||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
|
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 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) ? GET_PIN_MAP_INDEX((port << 5) | pin) : -2;
|
const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2;
|
||||||
return ind > -1 ? ind : dval;
|
return ind > -1 ? ind : dval;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -132,11 +132,40 @@ int freeMemory();
|
|||||||
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
|
// Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels)
|
||||||
|
|
||||||
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
|
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
|
||||||
#define HAL_adc_init() FilteredADC::init()
|
|
||||||
|
extern uint32_t HAL_adc_reading;
|
||||||
|
[[gnu::always_inline]] inline void HAL_start_adc(const pin_t pin) {
|
||||||
|
HAL_adc_reading = FilteredADC::read(pin) >> 6; // returns 16bit value, reduce to 10bit
|
||||||
|
}
|
||||||
|
[[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_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
|
||||||
#define HAL_START_ADC(pin) FilteredADC::start_conversion(pin)
|
#define HAL_START_ADC(pin) HAL_start_adc(pin)
|
||||||
#define HAL_READ_ADC() FilteredADC::get_result()
|
#define HAL_READ_ADC() HAL_read_adc()
|
||||||
#define HAL_ADC_READY() FilteredADC::finished_conversion()
|
#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
|
// Parse a G-code word into a pin index
|
||||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
|
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
|
||||||
|
@ -125,18 +125,18 @@
|
|||||||
PinCfg.Funcnum = 2;
|
PinCfg.Funcnum = 2;
|
||||||
PinCfg.OpenDrain = 0;
|
PinCfg.OpenDrain = 0;
|
||||||
PinCfg.Pinmode = 0;
|
PinCfg.Pinmode = 0;
|
||||||
PinCfg.Pinnum = LPC1768_PIN_PIN(SCK_PIN);
|
PinCfg.Pinnum = LPC176x::pin_bit(SCK_PIN);
|
||||||
PinCfg.Portnum = LPC1768_PIN_PORT(SCK_PIN);
|
PinCfg.Portnum = LPC176x::pin_port(SCK_PIN);
|
||||||
PINSEL_ConfigPin(&PinCfg);
|
PINSEL_ConfigPin(&PinCfg);
|
||||||
SET_OUTPUT(SCK_PIN);
|
SET_OUTPUT(SCK_PIN);
|
||||||
|
|
||||||
PinCfg.Pinnum = LPC1768_PIN_PIN(MISO_PIN);
|
PinCfg.Pinnum = LPC176x::pin_bit(MISO_PIN);
|
||||||
PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN);
|
PinCfg.Portnum = LPC176x::pin_port(MISO_PIN);
|
||||||
PINSEL_ConfigPin(&PinCfg);
|
PINSEL_ConfigPin(&PinCfg);
|
||||||
SET_INPUT(MISO_PIN);
|
SET_INPUT(MISO_PIN);
|
||||||
|
|
||||||
PinCfg.Pinnum = LPC1768_PIN_PIN(MOSI_PIN);
|
PinCfg.Pinnum = LPC176x::pin_bit(MOSI_PIN);
|
||||||
PinCfg.Portnum = LPC1768_PIN_PORT(MOSI_PIN);
|
PinCfg.Portnum = LPC176x::pin_port(MOSI_PIN);
|
||||||
PINSEL_ConfigPin(&PinCfg);
|
PINSEL_ConfigPin(&PinCfg);
|
||||||
SET_OUTPUT(MOSI_PIN);
|
SET_OUTPUT(MOSI_PIN);
|
||||||
// divide PCLK by 2 for SSP0
|
// divide PCLK by 2 for SSP0
|
||||||
|
@ -42,6 +42,8 @@ void endstop_ISR() { endstops.update(); }
|
|||||||
|
|
||||||
void setup_endstop_interrupts() {
|
void setup_endstop_interrupts() {
|
||||||
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
|
#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 HAS_X_MAX
|
||||||
#if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN)
|
#if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN)
|
||||||
#error "X_MAX_PIN is not INTERRUPT-capable."
|
#error "X_MAX_PIN is not INTERRUPT-capable."
|
||||||
|
@ -29,11 +29,11 @@
|
|||||||
#include <pwm.h>
|
#include <pwm.h>
|
||||||
|
|
||||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||||
pwm_set_frequency(pin, 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*/) {
|
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
|
||||||
pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size);
|
LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // FAST_PWM_FAN || SPINDLE_LASER_PWM
|
#endif // FAST_PWM_FAN || SPINDLE_LASER_PWM
|
||||||
|
@ -37,19 +37,19 @@
|
|||||||
|
|
||||||
#define PWM_PIN(P) true // all pins are PWM capable
|
#define PWM_PIN(P) true // all pins are PWM capable
|
||||||
|
|
||||||
#define LPC_PIN(pin) gpio_pin(pin)
|
#define LPC_PIN(pin) LPC176x::gpio_pin(pin)
|
||||||
#define LPC_GPIO(port) gpio_port(port)
|
#define LPC_GPIO(port) LPC176x::gpio_port(port)
|
||||||
|
|
||||||
#define SET_DIR_INPUT(IO) gpio_set_input(IO)
|
#define SET_DIR_INPUT(IO) LPC176x::gpio_set_input(IO)
|
||||||
#define SET_DIR_OUTPUT(IO) gpio_set_output(IO)
|
#define SET_DIR_OUTPUT(IO) LPC176x::gpio_set_output(IO)
|
||||||
|
|
||||||
#define SET_MODE(IO, mode) pinMode(IO, mode)
|
#define SET_MODE(IO, mode) pinMode(IO, mode)
|
||||||
|
|
||||||
#define WRITE_PIN_SET(IO) gpio_set(IO)
|
#define WRITE_PIN_SET(IO) LPC176x::gpio_set(IO)
|
||||||
#define WRITE_PIN_CLR(IO) gpio_clear(IO)
|
#define WRITE_PIN_CLR(IO) LPC176x::gpio_clear(IO)
|
||||||
|
|
||||||
#define READ_PIN(IO) gpio_get(IO)
|
#define READ_PIN(IO) LPC176x::gpio_get(IO)
|
||||||
#define WRITE_PIN(IO,V) gpio_set(IO, V)
|
#define WRITE_PIN(IO,V) LPC176x::gpio_set(IO, V)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Magic I/O routines
|
* Magic I/O routines
|
||||||
@ -81,10 +81,10 @@
|
|||||||
#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT)
|
#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT)
|
||||||
|
|
||||||
/// check if pin is an input
|
/// check if pin is an input
|
||||||
#define _IS_INPUT(IO) (!gpio_get_dir(IO))
|
#define _IS_INPUT(IO) (!LPC176x::gpio_get_dir(IO))
|
||||||
|
|
||||||
/// check if pin is an output
|
/// check if pin is an output
|
||||||
#define _IS_OUTPUT(IO) (gpio_get_dir(IO))
|
#define _IS_OUTPUT(IO) (LPC176x::gpio_get_dir(IO))
|
||||||
|
|
||||||
/// Read a pin wrapper
|
/// Read a pin wrapper
|
||||||
#define READ(IO) _READ(IO)
|
#define READ(IO) _READ(IO)
|
||||||
|
@ -21,6 +21,13 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#if PIO_PLATFORM_VERSION < 000001000
|
||||||
|
#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 < 000002000
|
||||||
|
#error "framework-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries."
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Test LPC176x-specific configuration values for errors at compile-time.
|
* Test LPC176x-specific configuration values for errors at compile-time.
|
||||||
*/
|
*/
|
||||||
|
@ -33,52 +33,21 @@
|
|||||||
#define PRINT_PORT(p)
|
#define PRINT_PORT(p)
|
||||||
#define GET_ARRAY_PIN(p) pin_array[p].pin
|
#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_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"), LPC1768_PIN_PORT(p), LPC1768_PIN_PIN(p)); 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
|
#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
|
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||||
// uses pin index
|
|
||||||
#ifndef M43_NEVER_TOUCH
|
#ifndef M43_NEVER_TOUCH
|
||||||
#define M43_NEVER_TOUCH(Q) ((Q) == 29 || (Q) == 30 || (Q) == 73) // USB pins
|
#define M43_NEVER_TOUCH(Q) ((Q) == P0_29 || (Q) == P0_30 || (Q) == P2_09) // USB pins
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// active ADC function/mode/code values for PINSEL registers
|
bool GET_PINMODE(const pin_t pin) {
|
||||||
constexpr int8_t ADC_pin_mode(pin_t pin) {
|
if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // found an invalid pin or active analog pin
|
||||||
return (LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 2 ? 2 :
|
|
||||||
LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 3 ? 2 :
|
|
||||||
LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 23 ? 1 :
|
|
||||||
LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 24 ? 1 :
|
|
||||||
LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 25 ? 1 :
|
|
||||||
LPC1768_PIN_PORT(pin) == 0 && LPC1768_PIN_PIN(pin) == 26 ? 1 :
|
|
||||||
LPC1768_PIN_PORT(pin) == 1 && LPC1768_PIN_PIN(pin) == 30 ? 3 :
|
|
||||||
LPC1768_PIN_PORT(pin) == 1 && LPC1768_PIN_PIN(pin) == 31 ? 3 : -1);
|
|
||||||
}
|
|
||||||
|
|
||||||
int8_t get_pin_mode(pin_t pin) {
|
|
||||||
if (!VALID_PIN(pin)) return -1;
|
|
||||||
uint8_t pin_port = LPC1768_PIN_PORT(pin);
|
|
||||||
uint8_t pin_port_pin = LPC1768_PIN_PIN(pin);
|
|
||||||
//get appropriate PINSEL register
|
|
||||||
volatile uint32_t * pinsel_reg = (pin_port == 0 && pin_port_pin <= 15) ? &LPC_PINCON->PINSEL0 :
|
|
||||||
(pin_port == 0) ? &LPC_PINCON->PINSEL1 :
|
|
||||||
(pin_port == 1 && pin_port_pin <= 15) ? &LPC_PINCON->PINSEL2 :
|
|
||||||
pin_port == 1 ? &LPC_PINCON->PINSEL3 :
|
|
||||||
pin_port == 2 ? &LPC_PINCON->PINSEL4 :
|
|
||||||
pin_port == 3 ? &LPC_PINCON->PINSEL7 : &LPC_PINCON->PINSEL9;
|
|
||||||
uint8_t pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
|
|
||||||
int8_t pin_mode = (int8_t) ((*pinsel_reg >> pinsel_start_bit) & 0x3);
|
|
||||||
return pin_mode;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool GET_PINMODE(pin_t pin) {
|
|
||||||
int8_t pin_mode = get_pin_mode(pin);
|
|
||||||
if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin
|
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
uint32_t * FIO_reg[5] PROGMEM = {(uint32_t*) 0x2009C000,(uint32_t*) 0x2009C020,(uint32_t*) 0x2009C040,(uint32_t*) 0x2009C060,(uint32_t*) 0x2009C080};
|
return LPC176x::gpio_direction(pin);
|
||||||
return ((*FIO_reg[LPC1768_PIN_PORT(pin)] >> LPC1768_PIN_PIN(pin) & 1) != 0); //input/output state
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool GET_ARRAY_IS_DIGITAL(pin_t pin) {
|
bool GET_ARRAY_IS_DIGITAL(const pin_t pin) {
|
||||||
return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
|
return (!LPC176x::pin_has_adc(pin) || !LPC176x::pin_adc_enabled(pin));
|
||||||
}
|
}
|
||||||
|
@ -59,7 +59,7 @@
|
|||||||
typedef uint32_t hal_timer_t;
|
typedef uint32_t hal_timer_t;
|
||||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
|
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
|
||||||
|
|
||||||
#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals
|
#define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals
|
||||||
|
|
||||||
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
|
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
|
||||||
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
|
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
|
||||||
|
@ -34,7 +34,7 @@
|
|||||||
#include <lpc17xx_libcfg_default.h>
|
#include <lpc17xx_libcfg_default.h>
|
||||||
|
|
||||||
#include "../../../core/millis_t.h"
|
#include "../../../core/millis_t.h"
|
||||||
|
extern int millis();
|
||||||
//////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
// These two routines are exact copies of the lpc17xx_i2c.c routines. Couldn't link to
|
// These two routines are exact copies of the lpc17xx_i2c.c routines. Couldn't link to
|
||||||
@ -151,14 +151,13 @@ void u8g_i2c_init(uint8_t clock_option) {
|
|||||||
u8g_i2c_start(0); // send slave address and write bit
|
u8g_i2c_start(0); // send slave address and write bit
|
||||||
}
|
}
|
||||||
|
|
||||||
volatile extern millis_t _millis;
|
|
||||||
uint8_t u8g_i2c_send_byte(uint8_t data) {
|
uint8_t u8g_i2c_send_byte(uint8_t data) {
|
||||||
#define I2C_TIMEOUT 3
|
#define I2C_TIMEOUT 3
|
||||||
LPC_I2C1->I2DAT = data & I2C_I2DAT_BITMASK; // transmit data
|
LPC_I2C1->I2DAT = data & I2C_I2DAT_BITMASK; // transmit data
|
||||||
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
|
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
|
||||||
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
|
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
|
||||||
const millis_t timeout = _millis + I2C_TIMEOUT;
|
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
|
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
|
// had hangs with SH1106 so added time out - have seen temporary screen corruption when this happens
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
@ -75,25 +75,25 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck
|
|||||||
|
|
||||||
for (uint8_t i = 0; i < 8; i++) {
|
for (uint8_t i = 0; i < 8; i++) {
|
||||||
if (spi_speed == 0) {
|
if (spi_speed == 0) {
|
||||||
gpio_set(mosi_pin, !!(b & 0x80));
|
LPC176x::gpio_set(mosi_pin, !!(b & 0x80));
|
||||||
gpio_set(sck_pin, HIGH);
|
LPC176x::gpio_set(sck_pin, HIGH);
|
||||||
b <<= 1;
|
b <<= 1;
|
||||||
if (miso_pin >= 0 && gpio_get(miso_pin)) b |= 1;
|
if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1;
|
||||||
gpio_set(sck_pin, LOW);
|
LPC176x::gpio_set(sck_pin, LOW);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
||||||
for (uint8_t j = 0; j < spi_speed; j++)
|
for (uint8_t j = 0; j < spi_speed; j++)
|
||||||
gpio_set(mosi_pin, state);
|
LPC176x::gpio_set(mosi_pin, state);
|
||||||
|
|
||||||
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
|
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
|
||||||
gpio_set(sck_pin, HIGH);
|
LPC176x::gpio_set(sck_pin, HIGH);
|
||||||
|
|
||||||
b <<= 1;
|
b <<= 1;
|
||||||
if (miso_pin >= 0 && gpio_get(miso_pin)) b |= 1;
|
if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1;
|
||||||
|
|
||||||
for (uint8_t j = 0; j < spi_speed; j++)
|
for (uint8_t j = 0; j < spi_speed; j++)
|
||||||
gpio_set(sck_pin, LOW);
|
LPC176x::gpio_set(sck_pin, LOW);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -105,23 +105,23 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck
|
|||||||
for (uint8_t i = 0; i < 8; i++) {
|
for (uint8_t i = 0; i < 8; i++) {
|
||||||
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
const uint8_t state = (b & 0x80) ? HIGH : LOW;
|
||||||
if (spi_speed == 0) {
|
if (spi_speed == 0) {
|
||||||
gpio_set(sck_pin, LOW);
|
LPC176x::gpio_set(sck_pin, LOW);
|
||||||
gpio_set(mosi_pin, state);
|
LPC176x::gpio_set(mosi_pin, state);
|
||||||
gpio_set(mosi_pin, state); // need some setup time
|
LPC176x::gpio_set(mosi_pin, state); // need some setup time
|
||||||
gpio_set(sck_pin, HIGH);
|
LPC176x::gpio_set(sck_pin, HIGH);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
|
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
|
||||||
gpio_set(sck_pin, LOW);
|
LPC176x::gpio_set(sck_pin, LOW);
|
||||||
|
|
||||||
for (uint8_t j = 0; j < spi_speed; j++)
|
for (uint8_t j = 0; j < spi_speed; j++)
|
||||||
gpio_set(mosi_pin, state);
|
LPC176x::gpio_set(mosi_pin, state);
|
||||||
|
|
||||||
for (uint8_t j = 0; j < spi_speed; j++)
|
for (uint8_t j = 0; j < spi_speed; j++)
|
||||||
gpio_set(sck_pin, HIGH);
|
LPC176x::gpio_set(sck_pin, HIGH);
|
||||||
}
|
}
|
||||||
b <<= 1;
|
b <<= 1;
|
||||||
if (miso_pin >= 0 && gpio_get(miso_pin)) b |= 1;
|
if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
return b;
|
return b;
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* AZSMZ MINI pin assignments
|
* AZSMZ MINI pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -71,9 +71,9 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 0 // A0 (TH1)
|
#define TEMP_0_PIN P0_23_A0 // A0 (TH1)
|
||||||
#define TEMP_BED_PIN 1 // A1 (TH2)
|
#define TEMP_BED_PIN P0_24_A1 // A1 (TH2)
|
||||||
#define TEMP_1_PIN 2 // A2 (TH3)
|
#define TEMP_1_PIN P0_25_A2 // A2 (TH3)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -21,7 +21,7 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -64,9 +64,9 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_BED_PIN 0 // Analog Input
|
#define TEMP_BED_PIN P0_23_A0 // Analog Input
|
||||||
#define TEMP_0_PIN 1 // Analog Input
|
#define TEMP_0_PIN P0_24_A1 // Analog Input
|
||||||
#define TEMP_1_PIN 2 // Analog Input
|
#define TEMP_1_PIN P0_25_A2 // Analog Input
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -21,7 +21,7 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -160,9 +160,9 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_BED_PIN 0 // A0 (T0) - (67) - TEMP_BED_PIN
|
#define TEMP_BED_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_BED_PIN
|
||||||
#define TEMP_0_PIN 1 // A1 (T1) - (68) - TEMP_0_PIN
|
#define TEMP_0_PIN P0_24_A1 // A1 (T1) - (68) - TEMP_0_PIN
|
||||||
#define TEMP_1_PIN 2 // A2 (T2) - (69) - TEMP_1_PIN
|
#define TEMP_1_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_1_PIN
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -30,7 +30,7 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -98,8 +98,8 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 1 // A0 (T0)
|
#define TEMP_0_PIN P0_24_A1 // A0 (T0)
|
||||||
#define TEMP_BED_PIN 0 // A1 (T1)
|
#define TEMP_BED_PIN P0_23_A0 // A1 (T1)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -30,7 +30,7 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -71,8 +71,8 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 0 // A0 (T0)
|
#define TEMP_0_PIN P0_23_A0 // A0 (T0)
|
||||||
#define TEMP_BED_PIN 1 // A1 (T1)
|
#define TEMP_BED_PIN P0_24_A1 // A1 (T1)
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -21,7 +21,7 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -103,8 +103,8 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 1 // AD0[0] on P0_23
|
#define TEMP_0_PIN P0_24_A1 // AD0[0] on P0_23
|
||||||
#define TEMP_BED_PIN 0 // AD0[1] on P0_24
|
#define TEMP_BED_PIN P0_23_A0 // AD0[1] on P0_24
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* MKS SBASE pin assignments
|
* MKS SBASE pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -90,10 +90,10 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_BED_PIN 0 // A0 (TH1)
|
#define TEMP_BED_PIN P0_23_A0 // A0 (TH1)
|
||||||
#define TEMP_0_PIN 1 // A1 (TH2)
|
#define TEMP_0_PIN P0_24_A1 // A1 (TH2)
|
||||||
#define TEMP_1_PIN 2 // A2 (TH3)
|
#define TEMP_1_PIN P0_25_A2 // A2 (TH3)
|
||||||
#define TEMP_2_PIN 3 // A3 (TH4)
|
#define TEMP_2_PIN P0_26_A3 // A3 (TH4)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* MKS SGEN-L pin assignments
|
* MKS SGEN-L pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -155,9 +155,9 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 0 // Analog Input A0 (TH1)
|
#define TEMP_0_PIN P0_23_A0 // Analog Input A0 (TH1)
|
||||||
#define TEMP_BED_PIN 1 // Analog Input A1 (TB)
|
#define TEMP_BED_PIN P0_24_A1 // Analog Input A1 (TB)
|
||||||
#define TEMP_1_PIN 2 // Analog Input A2 (TH2)
|
#define TEMP_1_PIN P0_25_A2 // Analog Input A2 (TH2)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -36,7 +36,7 @@
|
|||||||
|
|
||||||
// Numbers in parentheses () are the corresponding mega2560 pin numbers
|
// Numbers in parentheses () are the corresponding mega2560 pin numbers
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -162,14 +162,14 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 0 // A0 (T0) - (67) - TEMP_0_PIN
|
#define TEMP_0_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_0_PIN
|
||||||
#define TEMP_BED_PIN 1 // A1 (T1) - (68) - TEMP_BED_PIN
|
#define TEMP_BED_PIN P0_24_A1 // A1 (T1) - (68) - TEMP_BED_PIN
|
||||||
#define TEMP_1_PIN 2 // A2 (T2) - (69) - TEMP_1_PIN
|
#define TEMP_1_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_1_PIN
|
||||||
#define TEMP_2_PIN 3 // A3 - (63) - J5-3 & AUX-2
|
#define TEMP_2_PIN P0_26_A3 // A3 - (63) - J5-3 & AUX-2
|
||||||
#define TEMP_3_PIN 4 // A4 - (37) - BUZZER_PIN
|
#define TEMP_3_PIN P1_30_A4 // A4 - (37) - BUZZER_PIN
|
||||||
//#define TEMP_4_PIN 5 // A5 - (49) - SD_DETECT_PIN
|
//#define TEMP_4_PIN P1_31_A5 // A5 - (49) - SD_DETECT_PIN
|
||||||
//#define ?? 6 // A6 - ( 0) - RXD0 - J4-4 & AUX-1
|
//#define ?? P0_03_A6 // A6 - ( 0) - RXD0 - J4-4 & AUX-1
|
||||||
#define FILWIDTH_PIN 7 // A7 - ( 1) - TXD0 - J4-5 & AUX-1
|
#define FILWIDTH_PIN P0_02_A7 // A7 - ( 1) - TXD0 - J4-5 & AUX-1
|
||||||
|
|
||||||
//
|
//
|
||||||
// Augmentation for auto-assigning RAMPS plugs
|
// Augmentation for auto-assigning RAMPS plugs
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* Selena Compact pin assignments
|
* Selena Compact pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef TARGET_LPC1768
|
#ifndef MCU_LPC1768
|
||||||
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1768 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -75,9 +75,9 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_BED_PIN 0 // A0 (TH1)
|
#define TEMP_BED_PIN P0_23_A0 // A0 (TH1)
|
||||||
#define TEMP_0_PIN 1 // A1 (TH2)
|
#define TEMP_0_PIN P0_24_A1 // A1 (TH2)
|
||||||
#define TEMP_1_PIN 2 // A2 (TH3)
|
#define TEMP_1_PIN P0_25_A2 // A2 (TH3)
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -25,19 +25,13 @@
|
|||||||
* Azteeg X5 GT pin assignments
|
* Azteeg X5 GT pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BOARD_INFO_NAME "Azteeg X5 GT"
|
#define BOARD_INFO_NAME "Azteeg X5 GT"
|
||||||
#define BOARD_WEBSITE_URL "tinyurl.com/yx8tdqa3"
|
#define BOARD_WEBSITE_URL "tinyurl.com/yx8tdqa3"
|
||||||
|
|
||||||
//
|
|
||||||
// Custom CPU Speed 120MHz
|
|
||||||
//
|
|
||||||
#undef F_CPU
|
|
||||||
#define F_CPU 120000000
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// Servos
|
// Servos
|
||||||
//
|
//
|
||||||
@ -96,9 +90,9 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_BED_PIN 0 // A0 (TH1)
|
#define TEMP_BED_PIN P0_23_A0 // A0 (TH1)
|
||||||
#define TEMP_0_PIN 1 // A1 (TH2)
|
#define TEMP_0_PIN P0_24_A1 // A1 (TH2)
|
||||||
#define TEMP_1_PIN 2 // A2 (TH3)
|
#define TEMP_1_PIN P0_25_A2 // A2 (TH3)
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* Azteeg X5 MINI pin assignments
|
* Azteeg X5 MINI pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -56,7 +56,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef FILWIDTH_PIN
|
#ifndef FILWIDTH_PIN
|
||||||
#define FILWIDTH_PIN 2 // Analog Input (P0_25)
|
#define FILWIDTH_PIN P0_25_A2 // Analog Input (P0_25)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
@ -93,8 +93,8 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_BED_PIN 0 // A0 (TH1)
|
#define TEMP_BED_PIN P0_23_A0 // A0 (TH1)
|
||||||
#define TEMP_0_PIN 1 // A1 (TH2)
|
#define TEMP_0_PIN P0_24_A1 // A1 (TH2)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* Azteeg X5 MINI pin assignments
|
* Azteeg X5 MINI pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* Cohesion3D Mini pin assignments
|
* Cohesion3D Mini pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -88,8 +88,8 @@
|
|||||||
// Analog Inputs
|
// Analog Inputs
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 0 // P0_23
|
#define TEMP_0_PIN P0_23_A0 // P0_23
|
||||||
#define TEMP_BED_PIN 1 // P0_24
|
#define TEMP_BED_PIN P0_24_A1 // P0_24
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* Cohesion3D ReMix pin assignments
|
* Cohesion3D ReMix pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -98,13 +98,13 @@
|
|||||||
// Analog Inputs
|
// Analog Inputs
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 0 // P0_23
|
#define TEMP_0_PIN P0_23_A0
|
||||||
#define TEMP_BED_PIN 1 // P0_24
|
#define TEMP_BED_PIN P0_24_A1
|
||||||
#define TEMP_1_PIN 2 // P0_25
|
#define TEMP_1_PIN P0_25_A2
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define FILWIDTH_PIN 3 // P0_26
|
#define FILWIDTH_PIN P0_26_A3
|
||||||
#else
|
#else
|
||||||
#define TEMP_2_PIN 3 // P0_26
|
#define TEMP_2_PIN P0_26_A3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* MKS SGen pin assignments
|
* MKS SGen pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -25,19 +25,13 @@
|
|||||||
* Smoothieboard pin assignments
|
* Smoothieboard pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define BOARD_INFO_NAME "Smoothieboard"
|
#define BOARD_INFO_NAME "Smoothieboard"
|
||||||
#define BOARD_WEBSITE_URL "smoothieware.org/smoothieboard"
|
#define BOARD_WEBSITE_URL "smoothieware.org/smoothieboard"
|
||||||
|
|
||||||
//
|
|
||||||
// Custom CPU Speed 120MHz
|
|
||||||
//
|
|
||||||
#undef F_CPU
|
|
||||||
#define F_CPU 120000000
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// Servos
|
// Servos
|
||||||
//
|
//
|
||||||
@ -80,10 +74,10 @@
|
|||||||
// Temperature Sensors
|
// Temperature Sensors
|
||||||
// 3.3V max when defined as an analog input
|
// 3.3V max when defined as an analog input
|
||||||
//
|
//
|
||||||
#define TEMP_0_PIN 0 // P0.23 (T1)
|
#define TEMP_0_PIN P0_23_A0 // (T1)
|
||||||
#define TEMP_BED_PIN 1 // P0.24 (T2)
|
#define TEMP_BED_PIN P0_24_A1 // (T2)
|
||||||
#define TEMP_1_PIN 2 // P0.25 (T3)
|
#define TEMP_1_PIN P0_25_A2 // (T3)
|
||||||
#define TEMP_2_PIN 3 // P0.26 (T4)
|
#define TEMP_2_PIN P0_26_A3 // (T4)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Heaters / Fans
|
// Heaters / Fans
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
* TH3D EZBoard pin assignments
|
* TH3D EZBoard pin assignments
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef LPC1769
|
#ifndef MCU_LPC1769
|
||||||
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
#error "Oops! Make sure you have the LPC1769 environment selected in your IDE."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -94,18 +94,18 @@
|
|||||||
// 3.3V max when defined as an Analog Input!
|
// 3.3V max when defined as an Analog Input!
|
||||||
//
|
//
|
||||||
#if TEMP_SENSOR_0 == 20 // PT100 Adapter
|
#if TEMP_SENSOR_0 == 20 // PT100 Adapter
|
||||||
#define TEMP_0_PIN 7 // Analog Input
|
#define TEMP_0_PIN P0_02_A7 // Analog Input
|
||||||
#else
|
#else
|
||||||
#define TEMP_0_PIN 0 // Analog Input P0_23
|
#define TEMP_0_PIN P0_23_A0 // Analog Input P0_23
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define TEMP_BED_PIN 1 // Analog Input P0_24
|
#define TEMP_BED_PIN P0_24_A1 // Analog Input P0_24
|
||||||
#define TEMP_1_PIN 2 // Analog Input P0_25
|
#define TEMP_1_PIN P0_25_A2 // Analog Input P0_25
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define FILWIDTH_PIN 3 // Analog Input P0_26
|
#define FILWIDTH_PIN P0_26_A3 // Analog Input P0_26
|
||||||
#else
|
#else
|
||||||
#define TEMP_2_PIN 3 // Analog Input P0_26
|
#define TEMP_2_PIN P0_26_A3 // Analog Input P0_26
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -144,10 +144,10 @@ monitor_speed = 250000
|
|||||||
# NXP LPC176x ARM Cortex-M3
|
# NXP LPC176x ARM Cortex-M3
|
||||||
#
|
#
|
||||||
[env:LPC1768]
|
[env:LPC1768]
|
||||||
platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/master.zip
|
platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.0.zip
|
||||||
framework = arduino
|
framework = arduino
|
||||||
board = nxp_lpc1768
|
board = nxp_lpc1768
|
||||||
build_flags = -DTARGET_LPC1768 -DU8G_HAL_LINKS -IMarlin/src/HAL/HAL_LPC1768/include -IMarlin/src/HAL/HAL_LPC1768/u8g ${common.build_flags}
|
build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/HAL_LPC1768/include -IMarlin/src/HAL/HAL_LPC1768/u8g ${common.build_flags}
|
||||||
# debug options for backtrace
|
# debug options for backtrace
|
||||||
# -funwind-tables
|
# -funwind-tables
|
||||||
# -mpoke-function-name
|
# -mpoke-function-name
|
||||||
@ -159,15 +159,15 @@ monitor_speed = 250000
|
|||||||
lib_deps = Servo
|
lib_deps = Servo
|
||||||
LiquidCrystal
|
LiquidCrystal
|
||||||
U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip
|
U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip
|
||||||
TMCStepper@>=0.5.0,<1.0.0
|
TMCStepper=https://github.com/p3p/TMCStepper/archive/pr_lpctimingfix.zip
|
||||||
Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/master.zip
|
Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/release.zip
|
||||||
SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip
|
SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip
|
||||||
|
|
||||||
[env:LPC1769]
|
[env:LPC1769]
|
||||||
platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/master.zip
|
platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.0.zip
|
||||||
framework = arduino
|
framework = arduino
|
||||||
board = nxp_lpc1769
|
board = nxp_lpc1769
|
||||||
build_flags = -DTARGET_LPC1768 -DLPC1769 -DU8G_HAL_LINKS -IMarlin/src/HAL/HAL_LPC1768/include -IMarlin/src/HAL/HAL_LPC1768/u8g ${common.build_flags}
|
build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/HAL_LPC1768/include -IMarlin/src/HAL/HAL_LPC1768/u8g ${common.build_flags}
|
||||||
# debug options for backtrace
|
# debug options for backtrace
|
||||||
# -funwind-tables
|
# -funwind-tables
|
||||||
# -mpoke-function-name
|
# -mpoke-function-name
|
||||||
@ -179,8 +179,8 @@ monitor_speed = 250000
|
|||||||
lib_deps = Servo
|
lib_deps = Servo
|
||||||
LiquidCrystal
|
LiquidCrystal
|
||||||
U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip
|
U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip
|
||||||
TMCStepper@>=0.5.0,<1.0.0
|
TMCStepper=https://github.com/p3p/TMCStepper/archive/pr_lpctimingfix.zip
|
||||||
Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/master.zip
|
Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/release.zip
|
||||||
|
|
||||||
#
|
#
|
||||||
# Sanguinololu (ATmega644p)
|
# Sanguinololu (ATmega644p)
|
||||||
|
Loading…
Reference in New Issue
Block a user