mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2025-03-15 02:36:19 +00:00
Merge remote-tracking branch 'refs/remotes/MarlinFirmware/bugfix-2.0.x' into bugfix-2.0x
This commit is contained in:
commit
dd372505a0
156 changed files with 3904 additions and 2342 deletions
4
.gitignore
vendored
4
.gitignore
vendored
|
@ -158,9 +158,7 @@ vc-fileutils.settings
|
|||
|
||||
#Visual Studio Code
|
||||
.vscode
|
||||
|
||||
#Visual Studio Code
|
||||
.vscode
|
||||
.vscode/c_cpp_properties.json
|
||||
|
||||
#cmake
|
||||
CMakeLists.txt
|
||||
|
|
13
.travis.yml
13
.travis.yml
|
@ -61,7 +61,7 @@ script:
|
|||
- opt_set TEMP_SENSOR_BED 1
|
||||
- opt_enable PIDTEMPBED Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES
|
||||
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS
|
||||
- opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_RGBW_LED
|
||||
- opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_LED
|
||||
- build_marlin_pio ${TRAVIS_BUILD_DIR} ${TEST_PLATFORM}
|
||||
|
||||
#
|
||||
|
@ -436,3 +436,14 @@ script:
|
|||
- pins_set RAMPS X_MAX_PIN -1
|
||||
- opt_set_adv Z2_MAX_PIN 2
|
||||
- build_marlin_pio ${TRAVIS_BUILD_DIR} ${TEST_PLATFORM}
|
||||
|
||||
#############################
|
||||
# LPC1768 default config test
|
||||
#############################
|
||||
|
||||
- export TEST_PLATFORM="-e LPC1768"
|
||||
- restore_configs
|
||||
- opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB
|
||||
- cp Marlin/Configuration.h Marlin/src/config/default/Configuration.h
|
||||
- cp Marlin/Configuration_adv.h Marlin/src/config/default/Configuration_adv.h
|
||||
- build_marlin_pio ${TRAVIS_BUILD_DIR} ${TEST_PLATFORM}
|
||||
|
|
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -628,7 +637,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -66,9 +66,11 @@
|
|||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define HAL_TIMER_TYPE uint16_t
|
||||
typedef uint16_t timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFF
|
||||
|
||||
typedef int8_t pin_t;
|
||||
|
||||
#define HAL_SERVO_LIB Servo
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
@ -153,4 +155,10 @@ inline void HAL_adc_init(void) {
|
|||
|
||||
#define HAL_READ_ADC ADC
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
||||
#define HAL_SENSITIVE_PINS 0, 1
|
||||
|
||||
#endif // _HAL_AVR_H_
|
||||
|
|
|
@ -82,7 +82,7 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) {
|
|||
|
||||
typedef struct {
|
||||
const char * const name;
|
||||
uint8_t pin;
|
||||
pin_t pin;
|
||||
bool is_digital;
|
||||
} PinInfo;
|
||||
|
||||
|
@ -457,7 +457,7 @@ static void print_input_or_output(const bool isout) {
|
|||
}
|
||||
|
||||
// pretty report with PWM info
|
||||
inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false, const char *start_string = "") {
|
||||
inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = false, const char *start_string = "") {
|
||||
uint8_t temp_char;
|
||||
char *name_mem_pointer, buffer[30]; // for the sprintf statements
|
||||
bool found = false, multi_name_pin = false;
|
||||
|
|
|
@ -84,7 +84,7 @@
|
|||
// Currently looking for: M108, M112, M410
|
||||
// If you alter the parser please don't forget to update the capabilities in Conditionals_post.h
|
||||
|
||||
FORCE_INLINE void emergency_parser(const unsigned char c) {
|
||||
FORCE_INLINE void emergency_parser(const uint8_t c) {
|
||||
|
||||
static e_parser_state state = state_RESET;
|
||||
|
||||
|
@ -169,13 +169,16 @@
|
|||
#endif // EMERGENCY_PARSER
|
||||
|
||||
FORCE_INLINE void store_rxd_char() {
|
||||
|
||||
const ring_buffer_pos_t h = rx_buffer.head,
|
||||
i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
|
||||
|
||||
// Read the character
|
||||
const uint8_t c = M_UDRx;
|
||||
|
||||
// If the character is to be stored at the index just before the tail
|
||||
// (such that the head would advance to the current tail), the buffer is
|
||||
// critical, so don't write the character or advance the head.
|
||||
const char c = M_UDRx;
|
||||
if (i != rx_buffer.tail) {
|
||||
rx_buffer.buffer[h] = c;
|
||||
rx_buffer.head = i;
|
||||
|
@ -194,6 +197,7 @@
|
|||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
|
||||
// for high speed transfers, we can use XON/XOFF protocol to do
|
||||
// software handshake and avoid overruns.
|
||||
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
|
||||
|
|
|
@ -397,6 +397,6 @@ static void pwm_details(uint8_t pin) {
|
|||
|
||||
#endif
|
||||
|
||||
#define GET_PIN_INFO(pin) do{}while(0)
|
||||
#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer);} while (0)
|
||||
|
||||
#endif // _PINSDEBUG_AVR_8_BIT_
|
||||
|
|
|
@ -29,37 +29,35 @@
|
|||
#ifndef _HAL_DUE_H
|
||||
#define _HAL_DUE_H
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "Arduino.h"
|
||||
|
||||
#include "fastio_Due.h"
|
||||
#include "watchdog_Due.h"
|
||||
|
||||
#include "HAL_timers_Due.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
//
|
||||
// Defines
|
||||
// --------------------------------------------------------------------------
|
||||
//
|
||||
|
||||
#if SERIAL_PORT == -1
|
||||
#define MYSERIAL SerialUSB
|
||||
#elif SERIAL_PORT == 0
|
||||
#define MYSERIAL Serial
|
||||
#define MYSERIAL customizedSerial
|
||||
#elif SERIAL_PORT == 1
|
||||
#define MYSERIAL Serial1
|
||||
#define MYSERIAL customizedSerial
|
||||
#elif SERIAL_PORT == 2
|
||||
#define MYSERIAL Serial2
|
||||
#define MYSERIAL customizedSerial
|
||||
#elif SERIAL_PORT == 3
|
||||
#define MYSERIAL Serial3
|
||||
#define MYSERIAL customizedSerial
|
||||
#endif
|
||||
|
||||
#define _BV(bit) (1 << (bit))
|
||||
|
||||
// We need the previous define before the include, or compilation bombs...
|
||||
#include "MarlinSerial_Due.h"
|
||||
|
||||
#ifndef analogInputToDigitalPin
|
||||
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
|
||||
#endif
|
||||
|
@ -96,51 +94,49 @@
|
|||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
typedef int8_t pin_t;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/** result of last ADC conversion */
|
||||
extern uint16_t HAL_adc_result;
|
||||
extern uint16_t HAL_adc_result; // result of last ADC conversion
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
void cli(void); // Disable interrupts
|
||||
void sei(void); // Enable interrupts
|
||||
|
||||
// Disable interrupts
|
||||
void cli(void);
|
||||
|
||||
// Enable interrupts
|
||||
void sei(void);
|
||||
|
||||
/** clear reset reason */
|
||||
void HAL_clear_reset_source (void);
|
||||
|
||||
/** reset reason */
|
||||
uint8_t HAL_get_reset_source (void);
|
||||
void HAL_clear_reset_source(void); // clear reset reason
|
||||
uint8_t HAL_get_reset_source(void); // get reset reason
|
||||
|
||||
void _delay_ms(const int delay);
|
||||
|
||||
int freeMemory(void);
|
||||
|
||||
// SPI: Extended functions which take a channel number (hardware SPI only)
|
||||
/** Write single byte to specified SPI channel */
|
||||
/**
|
||||
* SPI: Extended functions taking a channel number (hardware SPI only)
|
||||
*/
|
||||
|
||||
// Write single byte to specified SPI channel
|
||||
void spiSend(uint32_t chan, byte b);
|
||||
/** Write buffer to specified SPI channel */
|
||||
|
||||
// Write buffer to specified SPI channel
|
||||
void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
|
||||
/** Read single byte from specified SPI channel */
|
||||
|
||||
// Read single byte from specified SPI channel
|
||||
uint8_t spiRec(uint32_t chan);
|
||||
|
||||
/**
|
||||
* EEPROM
|
||||
*/
|
||||
|
||||
// EEPROM
|
||||
void eeprom_write_byte(unsigned char *pos, unsigned char value);
|
||||
unsigned char eeprom_read_byte(unsigned char *pos);
|
||||
void eeprom_read_block (void *__dst, const void *__src, size_t __n);
|
||||
void eeprom_update_block (const void *__src, void *__dst, size_t __n);
|
||||
|
||||
|
||||
// ADC
|
||||
/**
|
||||
* ADC
|
||||
*/
|
||||
|
||||
#define HAL_ANALOG_SELECT(pin)
|
||||
|
||||
|
@ -149,27 +145,18 @@ inline void HAL_adc_init(void) {}//todo
|
|||
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
|
||||
#define HAL_READ_ADC HAL_adc_result
|
||||
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
|
||||
uint16_t HAL_adc_get_result(void);
|
||||
|
||||
//
|
||||
uint16_t HAL_getAdcReading(uint8_t chan);
|
||||
|
||||
void HAL_startAdcConversion(uint8_t chan);
|
||||
uint8_t HAL_pinToAdcChannel(int pin);
|
||||
|
||||
uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
|
||||
//uint16_t HAL_getAdcSuperSample(uint8_t chan);
|
||||
|
||||
void HAL_enable_AdcFreerun(void);
|
||||
//void HAL_disable_AdcFreerun(uint8_t chan);
|
||||
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
//
|
||||
// --------------------------------------------------------------------------
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
||||
#endif // _HAL_DUE_H
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
#define HAL_TIMER_TYPE uint32_t
|
||||
typedef uint32_t timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
|
||||
|
||||
#define STEP_TIMER_NUM 3 // index of timer to use for stepper
|
||||
|
@ -92,7 +92,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const uint
|
|||
pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = count;
|
||||
}
|
||||
|
||||
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
|
||||
static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||
const tTimerConfig *pConfig = &TimerConfig[timer_num];
|
||||
return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC;
|
||||
}
|
||||
|
|
95
Marlin/src/HAL/HAL_DUE/InterruptVectors_Due.cpp
Normal file
95
Marlin/src/HAL/HAL_DUE/InterruptVectors_Due.cpp
Normal file
|
@ -0,0 +1,95 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* InterruptVectors_Due.cpp - This module relocates the Interrupt vector table to SRAM,
|
||||
* allowing to register new interrupt handlers at runtime. Specially valuable and needed
|
||||
* because Arduino runtime allocates some interrupt handlers that we NEED to override to
|
||||
* properly support extended functionality, as for example, USB host or USB device (MSD, MTP)
|
||||
* and custom serial port handlers, and we don't actually want to modify and/or recompile the
|
||||
* Arduino runtime. We just want to run as much as possible on Stock Arduino
|
||||
*
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "HAL_Due.h"
|
||||
#include "InterruptVectors_Due.h"
|
||||
|
||||
/* The relocated Exception/Interrupt Table - Must be aligned to 128bytes,
|
||||
as bits 0-6 on VTOR register are reserved and must be set to 0 */
|
||||
__attribute__ ((aligned(128)))
|
||||
static DeviceVectors ram_tab = { NULL };
|
||||
|
||||
/**
|
||||
* This function checks if the exception/interrupt table is already in SRAM or not.
|
||||
* If it is not, then it copies the ROM table to the SRAM and relocates the table
|
||||
* by reprogramming the NVIC registers
|
||||
*/
|
||||
static pfnISR_Handler* get_relocated_table_addr(void) {
|
||||
// Get the address of the interrupt/exception table
|
||||
uint32_t isrtab = SCB->VTOR;
|
||||
|
||||
// If already relocated, we are done!
|
||||
if (isrtab >= IRAM0_ADDR)
|
||||
return (pfnISR_Handler*)isrtab;
|
||||
|
||||
// Get the address of the table stored in FLASH
|
||||
const pfnISR_Handler* romtab = (const pfnISR_Handler*)isrtab;
|
||||
|
||||
// Copy it to SRAM
|
||||
memcpy(&ram_tab, romtab, sizeof(ram_tab));
|
||||
|
||||
// Disable global interrupts
|
||||
CRITICAL_SECTION_START;
|
||||
|
||||
// Set the vector table base address to the SRAM copy
|
||||
SCB->VTOR = (uint32_t)(&ram_tab);
|
||||
|
||||
// Reenable interrupts
|
||||
CRITICAL_SECTION_END;
|
||||
|
||||
// Return the address of the table
|
||||
return (pfnISR_Handler*)(&ram_tab);
|
||||
}
|
||||
|
||||
pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler) {
|
||||
// Get the address of the relocated table
|
||||
const pfnISR_Handler *isrtab = get_relocated_table_addr();
|
||||
|
||||
// Disable global interrupts
|
||||
CRITICAL_SECTION_START;
|
||||
|
||||
// Get the original handler
|
||||
pfnISR_Handler oldHandler = isrtab[irq + 16];
|
||||
|
||||
// Install the new one
|
||||
isrtab[irq + 16] = newHandler;
|
||||
|
||||
// Reenable interrupts
|
||||
CRITICAL_SECTION_END;
|
||||
|
||||
// Return the original one
|
||||
return oldHandler;
|
||||
}
|
||||
|
||||
#endif
|
52
Marlin/src/HAL/HAL_DUE/InterruptVectors_Due.h
Normal file
52
Marlin/src/HAL/HAL_DUE/InterruptVectors_Due.h
Normal file
|
@ -0,0 +1,52 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* InterruptVectors_Due.h
|
||||
*
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
*
|
||||
* This module relocates the Interrupt vector table to SRAM, allowing new
|
||||
* interrupt handlers to be added at runtime. This is required because the
|
||||
* Arduino runtime steals interrupt handlers that Marlin MUST use to support
|
||||
* extended functionality such as USB hosts and USB devices (MSD, MTP) and
|
||||
* custom serial port handlers. Rather than modifying and/or recompiling the
|
||||
* Arduino runtime, We just want to run as much as possible on Stock Arduino.
|
||||
*
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
*/
|
||||
|
||||
#ifndef INTERRUPTVECTORS_DUE_H
|
||||
#define INTERRUPTVECTORS_DUE_H
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
// ISR handler type
|
||||
typedef void (*pfnISR_Handler)(void);
|
||||
|
||||
// Install a new interrupt vector handler for the given irq, returning the old one
|
||||
pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler);
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
||||
#endif // INTERRUPTVECTORS_DUE_H
|
680
Marlin/src/HAL/HAL_DUE/MarlinSerial_Due.cpp
Normal file
680
Marlin/src/HAL/HAL_DUE/MarlinSerial_Due.cpp
Normal file
|
@ -0,0 +1,680 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
* Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#include "MarlinSerial_Due.h"
|
||||
#include "InterruptVectors_Due.h"
|
||||
#include "../../Marlin.h"
|
||||
|
||||
// Based on selected port, use the proper configuration
|
||||
#if SERIAL_PORT == 0
|
||||
#define HWUART UART
|
||||
#define HWUART_IRQ UART_IRQn
|
||||
#define HWUART_IRQ_ID ID_UART
|
||||
#elif SERIAL_PORT == 1
|
||||
#define HWUART USART0
|
||||
#define HWUART_IRQ USART0_IRQn
|
||||
#define HWUART_IRQ_ID ID_USART0
|
||||
#elif SERIAL_PORT == 2
|
||||
#define HWUART USART1
|
||||
#define HWUART_IRQ USART1_IRQn
|
||||
#define HWUART_IRQ_ID ID_USART1
|
||||
#elif SERIAL_PORT == 3
|
||||
#define HWUART USART3
|
||||
#define HWUART_IRQ USART3_IRQn
|
||||
#define HWUART_IRQ_ID ID_USART3
|
||||
#endif
|
||||
|
||||
struct ring_buffer_r {
|
||||
unsigned char buffer[RX_BUFFER_SIZE];
|
||||
volatile ring_buffer_pos_t head, tail;
|
||||
};
|
||||
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
struct ring_buffer_t {
|
||||
unsigned char buffer[TX_BUFFER_SIZE];
|
||||
volatile uint8_t head, tail;
|
||||
};
|
||||
#endif
|
||||
|
||||
ring_buffer_r rx_buffer = { { 0 }, 0, 0 };
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
ring_buffer_t tx_buffer = { { 0 }, 0, 0 };
|
||||
static bool _written;
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
constexpr uint8_t XON_XOFF_CHAR_SENT = 0x80; // XON / XOFF Character was sent
|
||||
constexpr uint8_t XON_XOFF_CHAR_MASK = 0x1F; // XON / XOFF character to send
|
||||
// XON / XOFF character definitions
|
||||
constexpr uint8_t XON_CHAR = 17;
|
||||
constexpr uint8_t XOFF_CHAR = 19;
|
||||
uint8_t xon_xoff_state = XON_XOFF_CHAR_SENT | XON_CHAR;
|
||||
|
||||
// Validate that RX buffer size is at least 4096 bytes- According to several experiments, on
|
||||
// the original Arduino Due that uses a ATmega16U2 as USB to serial bridge, due to the introduced
|
||||
// latencies, at least 2959 bytes of RX buffering (when transmitting at 250kbits/s) are required
|
||||
// to avoid overflows.
|
||||
|
||||
#if RX_BUFFER_SIZE < 4096
|
||||
#error Arduino DUE requires at least 4096 bytes of RX buffer to avoid buffer overflows when using XON/XOFF handshake
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
uint8_t rx_dropped_bytes = 0;
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
ring_buffer_pos_t rx_max_enqueued = 0;
|
||||
#endif
|
||||
|
||||
// A SW memory barrier, to ensure GCC does not overoptimize loops
|
||||
#define sw_barrier() asm volatile("": : :"memory");
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
|
||||
#include "../../module/stepper.h"
|
||||
|
||||
// Currently looking for: M108, M112, M410
|
||||
// If you alter the parser please don't forget to update the capabilities in Conditionals_post.h
|
||||
|
||||
FORCE_INLINE void emergency_parser(const uint8_t c) {
|
||||
|
||||
static e_parser_state state = state_RESET;
|
||||
|
||||
switch (state) {
|
||||
case state_RESET:
|
||||
switch (c) {
|
||||
case ' ': break;
|
||||
case 'N': state = state_N; break;
|
||||
case 'M': state = state_M; break;
|
||||
default: state = state_IGNORE;
|
||||
}
|
||||
break;
|
||||
|
||||
case state_N:
|
||||
switch (c) {
|
||||
case '0': case '1': case '2':
|
||||
case '3': case '4': case '5':
|
||||
case '6': case '7': case '8':
|
||||
case '9': case '-': case ' ': break;
|
||||
case 'M': state = state_M; break;
|
||||
default: state = state_IGNORE;
|
||||
}
|
||||
break;
|
||||
|
||||
case state_M:
|
||||
switch (c) {
|
||||
case ' ': break;
|
||||
case '1': state = state_M1; break;
|
||||
case '4': state = state_M4; break;
|
||||
default: state = state_IGNORE;
|
||||
}
|
||||
break;
|
||||
|
||||
case state_M1:
|
||||
switch (c) {
|
||||
case '0': state = state_M10; break;
|
||||
case '1': state = state_M11; break;
|
||||
default: state = state_IGNORE;
|
||||
}
|
||||
break;
|
||||
|
||||
case state_M10:
|
||||
state = (c == '8') ? state_M108 : state_IGNORE;
|
||||
break;
|
||||
|
||||
case state_M11:
|
||||
state = (c == '2') ? state_M112 : state_IGNORE;
|
||||
break;
|
||||
|
||||
case state_M4:
|
||||
state = (c == '1') ? state_M41 : state_IGNORE;
|
||||
break;
|
||||
|
||||
case state_M41:
|
||||
state = (c == '0') ? state_M410 : state_IGNORE;
|
||||
break;
|
||||
|
||||
case state_IGNORE:
|
||||
if (c == '\n') state = state_RESET;
|
||||
break;
|
||||
|
||||
default:
|
||||
if (c == '\n') {
|
||||
switch (state) {
|
||||
case state_M108:
|
||||
wait_for_user = wait_for_heatup = false;
|
||||
break;
|
||||
case state_M112:
|
||||
kill(PSTR(MSG_KILLED));
|
||||
break;
|
||||
case state_M410:
|
||||
quickstop_stepper();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
state = state_RESET;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // EMERGENCY_PARSER
|
||||
|
||||
FORCE_INLINE void store_rxd_char() {
|
||||
|
||||
const ring_buffer_pos_t h = rx_buffer.head,
|
||||
i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
|
||||
|
||||
// Read the character
|
||||
const uint8_t c = HWUART->UART_RHR;
|
||||
|
||||
// If the character is to be stored at the index just before the tail
|
||||
// (such that the head would advance to the current tail), the buffer is
|
||||
// critical, so don't write the character or advance the head.
|
||||
if (i != rx_buffer.tail) {
|
||||
rx_buffer.buffer[h] = c;
|
||||
rx_buffer.head = i;
|
||||
}
|
||||
#if ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
else if (!++rx_dropped_bytes) ++rx_dropped_bytes;
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
// calculate count of bytes stored into the RX buffer
|
||||
ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
|
||||
// Keep track of the maximum count of enqueued bytes
|
||||
NOLESS(rx_max_enqueued, rx_count);
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
|
||||
// for high speed transfers, we can use XON/XOFF protocol to do
|
||||
// software handshake and avoid overruns.
|
||||
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
|
||||
|
||||
// calculate count of bytes stored into the RX buffer
|
||||
ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
|
||||
|
||||
// if we are above 12.5% of RX buffer capacity, send XOFF before
|
||||
// we run out of RX buffer space .. We need 325 bytes @ 250kbits/s to
|
||||
// let the host react and stop sending bytes. This translates to 13mS
|
||||
// propagation time.
|
||||
if (rx_count >= (RX_BUFFER_SIZE) / 8) {
|
||||
// If TX interrupts are disabled and data register is empty,
|
||||
// just write the byte to the data register and be done. This
|
||||
// shortcut helps significantly improve the effective datarate
|
||||
// at high (>500kbit/s) bitrates, where interrupt overhead
|
||||
// becomes a slowdown.
|
||||
if (!(HWUART->UART_IMR & UART_IMR_TXRDY) && (HWUART->UART_SR & UART_SR_TXRDY)) {
|
||||
// Send an XOFF character
|
||||
HWUART->UART_THR = XOFF_CHAR;
|
||||
|
||||
// And remember it was sent
|
||||
xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
|
||||
}
|
||||
else {
|
||||
// TX interrupts disabled, but buffer still not empty ... or
|
||||
// TX interrupts enabled. Reenable TX ints and schedule XOFF
|
||||
// character to be sent
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
HWUART->UART_IER = UART_IER_TXRDY;
|
||||
xon_xoff_state = XOFF_CHAR;
|
||||
#else
|
||||
// We are not using TX interrupts, we will have to send this manually
|
||||
while (!(HWUART->UART_SR & UART_SR_TXRDY)) { sw_barrier(); };
|
||||
HWUART->UART_THR = XOFF_CHAR;
|
||||
// And remember we already sent it
|
||||
xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // SERIAL_XON_XOFF
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
emergency_parser(c);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
|
||||
FORCE_INLINE void _tx_thr_empty_irq(void) {
|
||||
// If interrupts are enabled, there must be more data in the output
|
||||
// buffer.
|
||||
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
// Do a priority insertion of an XON/XOFF char, if needed.
|
||||
const uint8_t state = xon_xoff_state;
|
||||
if (!(state & XON_XOFF_CHAR_SENT)) {
|
||||
HWUART->UART_THR = state & XON_XOFF_CHAR_MASK;
|
||||
xon_xoff_state = state | XON_XOFF_CHAR_SENT;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{ // Send the next byte
|
||||
const uint8_t t = tx_buffer.tail, c = tx_buffer.buffer[t];
|
||||
tx_buffer.tail = (t + 1) & (TX_BUFFER_SIZE - 1);
|
||||
HWUART->UART_THR = c;
|
||||
}
|
||||
|
||||
// Disable interrupts if the buffer is empty
|
||||
if (tx_buffer.head == tx_buffer.tail)
|
||||
HWUART->UART_IDR = UART_IDR_TXRDY;
|
||||
}
|
||||
|
||||
#endif // TX_BUFFER_SIZE
|
||||
|
||||
static void UART_ISR(void) {
|
||||
uint32_t status = HWUART->UART_SR;
|
||||
|
||||
// Did we receive data?
|
||||
if (status & UART_SR_RXRDY)
|
||||
store_rxd_char();
|
||||
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
// Do we have something to send, and TX interrupts are enabled (meaning something to send) ?
|
||||
if ((status & UART_SR_TXRDY) && (HWUART->UART_IMR & UART_IMR_TXRDY))
|
||||
_tx_thr_empty_irq();
|
||||
#endif
|
||||
|
||||
// Acknowledge errors
|
||||
if ((status & UART_SR_OVRE) || (status & UART_SR_FRAME)) {
|
||||
// TODO: error reporting outside ISR
|
||||
HWUART->UART_CR = UART_CR_RSTSTA;
|
||||
}
|
||||
}
|
||||
|
||||
// Public Methods
|
||||
|
||||
void MarlinSerial::begin(const long baud_setting) {
|
||||
|
||||
// Disable UART interrupt in NVIC
|
||||
NVIC_DisableIRQ( HWUART_IRQ );
|
||||
|
||||
// Disable clock
|
||||
pmc_disable_periph_clk( HWUART_IRQ_ID );
|
||||
|
||||
// Configure PMC
|
||||
pmc_enable_periph_clk( HWUART_IRQ_ID );
|
||||
|
||||
// Disable PDC channel
|
||||
HWUART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
|
||||
|
||||
// Reset and disable receiver and transmitter
|
||||
HWUART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
|
||||
|
||||
// Configure mode: 8bit, No parity, 1 bit stop
|
||||
HWUART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO;
|
||||
|
||||
// Configure baudrate (asynchronous, no oversampling)
|
||||
HWUART->UART_BRGR = (SystemCoreClock / (baud_setting << 4));
|
||||
|
||||
// Configure interrupts
|
||||
HWUART->UART_IDR = 0xFFFFFFFF;
|
||||
HWUART->UART_IER = UART_IER_RXRDY | UART_IER_OVRE | UART_IER_FRAME;
|
||||
|
||||
// Install interrupt handler
|
||||
install_isr(HWUART_IRQ, UART_ISR);
|
||||
|
||||
// Enable UART interrupt in NVIC
|
||||
NVIC_EnableIRQ(HWUART_IRQ);
|
||||
|
||||
// Enable receiver and transmitter
|
||||
HWUART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
|
||||
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
_written = false;
|
||||
#endif
|
||||
}
|
||||
|
||||
void MarlinSerial::end() {
|
||||
// Disable UART interrupt in NVIC
|
||||
NVIC_DisableIRQ( HWUART_IRQ );
|
||||
|
||||
pmc_disable_periph_clk( HWUART_IRQ_ID );
|
||||
}
|
||||
|
||||
void MarlinSerial::checkRx(void) {
|
||||
if (HWUART->UART_SR & UART_SR_RXRDY) {
|
||||
CRITICAL_SECTION_START;
|
||||
store_rxd_char();
|
||||
CRITICAL_SECTION_END;
|
||||
}
|
||||
}
|
||||
|
||||
int MarlinSerial::peek(void) {
|
||||
CRITICAL_SECTION_START;
|
||||
const int v = rx_buffer.head == rx_buffer.tail ? -1 : rx_buffer.buffer[rx_buffer.tail];
|
||||
CRITICAL_SECTION_END;
|
||||
return v;
|
||||
}
|
||||
|
||||
int MarlinSerial::read(void) {
|
||||
int v;
|
||||
CRITICAL_SECTION_START;
|
||||
const ring_buffer_pos_t t = rx_buffer.tail;
|
||||
if (rx_buffer.head == t)
|
||||
v = -1;
|
||||
else {
|
||||
v = rx_buffer.buffer[t];
|
||||
rx_buffer.tail = (ring_buffer_pos_t)(t + 1) & (RX_BUFFER_SIZE - 1);
|
||||
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
|
||||
// Get count of bytes in the RX buffer
|
||||
ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
|
||||
// When below 10% of RX buffer capacity, send XON before
|
||||
// running out of RX buffer bytes
|
||||
if (rx_count < (RX_BUFFER_SIZE) / 10) {
|
||||
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
|
||||
CRITICAL_SECTION_END; // End critical section before returning!
|
||||
writeNoHandshake(XON_CHAR);
|
||||
return v;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
CRITICAL_SECTION_END;
|
||||
return v;
|
||||
}
|
||||
|
||||
ring_buffer_pos_t MarlinSerial::available(void) {
|
||||
CRITICAL_SECTION_START;
|
||||
const ring_buffer_pos_t h = rx_buffer.head, t = rx_buffer.tail;
|
||||
CRITICAL_SECTION_END;
|
||||
return (ring_buffer_pos_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
|
||||
}
|
||||
|
||||
void MarlinSerial::flush(void) {
|
||||
// Don't change this order of operations. If the RX interrupt occurs between
|
||||
// reading rx_buffer_head and updating rx_buffer_tail, the previous rx_buffer_head
|
||||
// may be written to rx_buffer_tail, making the buffer appear full rather than empty.
|
||||
CRITICAL_SECTION_START;
|
||||
rx_buffer.head = rx_buffer.tail;
|
||||
CRITICAL_SECTION_END;
|
||||
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
|
||||
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
|
||||
writeNoHandshake(XON_CHAR);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
uint8_t MarlinSerial::availableForWrite(void) {
|
||||
CRITICAL_SECTION_START;
|
||||
const uint8_t h = tx_buffer.head, t = tx_buffer.tail;
|
||||
CRITICAL_SECTION_END;
|
||||
return (uint8_t)(TX_BUFFER_SIZE + h - t) & (TX_BUFFER_SIZE - 1);
|
||||
}
|
||||
|
||||
void MarlinSerial::write(const uint8_t c) {
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
const uint8_t state = xon_xoff_state;
|
||||
if (!(state & XON_XOFF_CHAR_SENT)) {
|
||||
// Send 2 chars: XON/XOFF, then a user-specified char
|
||||
writeNoHandshake(state & XON_XOFF_CHAR_MASK);
|
||||
xon_xoff_state = state | XON_XOFF_CHAR_SENT;
|
||||
}
|
||||
#endif
|
||||
writeNoHandshake(c);
|
||||
}
|
||||
|
||||
void MarlinSerial::writeNoHandshake(const uint8_t c) {
|
||||
_written = true;
|
||||
CRITICAL_SECTION_START;
|
||||
bool emty = (tx_buffer.head == tx_buffer.tail);
|
||||
CRITICAL_SECTION_END;
|
||||
// If the buffer and the data register is empty, just write the byte
|
||||
// to the data register and be done. This shortcut helps
|
||||
// significantly improve the effective datarate at high (>
|
||||
// 500kbit/s) bitrates, where interrupt overhead becomes a slowdown.
|
||||
if (emty && (HWUART->UART_SR & UART_SR_TXRDY)) {
|
||||
CRITICAL_SECTION_START;
|
||||
HWUART->UART_THR = c;
|
||||
HWUART->UART_IER = UART_IER_TXRDY;
|
||||
CRITICAL_SECTION_END;
|
||||
return;
|
||||
}
|
||||
const uint8_t i = (tx_buffer.head + 1) & (TX_BUFFER_SIZE - 1);
|
||||
|
||||
// If the output buffer is full, there's nothing for it other than to
|
||||
// wait for the interrupt handler to empty it a bit
|
||||
while (i == tx_buffer.tail) {
|
||||
if (__get_PRIMASK()) {
|
||||
// Interrupts are disabled, so we'll have to poll the data
|
||||
// register empty flag ourselves. If it is set, pretend an
|
||||
// interrupt has happened and call the handler to free up
|
||||
// space for us.
|
||||
if (HWUART->UART_SR & UART_SR_TXRDY)
|
||||
_tx_thr_empty_irq();
|
||||
}
|
||||
else {
|
||||
// nop, the interrupt handler will free up space for us
|
||||
}
|
||||
sw_barrier();
|
||||
}
|
||||
|
||||
tx_buffer.buffer[tx_buffer.head] = c;
|
||||
{ CRITICAL_SECTION_START;
|
||||
tx_buffer.head = i;
|
||||
HWUART->UART_IER = UART_IER_TXRDY;
|
||||
CRITICAL_SECTION_END;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
void MarlinSerial::flushTX(void) {
|
||||
// TX
|
||||
// If we have never written a byte, no need to flush.
|
||||
if (!_written)
|
||||
return;
|
||||
|
||||
while ((HWUART->UART_IMR & UART_IMR_TXRDY) || !(HWUART->UART_SR & UART_SR_TXEMPTY)) {
|
||||
if (__get_PRIMASK())
|
||||
if ((HWUART->UART_SR & UART_SR_TXRDY))
|
||||
_tx_thr_empty_irq();
|
||||
sw_barrier();
|
||||
}
|
||||
// If we get here, nothing is queued anymore (TX interrupts are disabled) and
|
||||
// the hardware finished tranmission (TXEMPTY is set).
|
||||
}
|
||||
|
||||
#else // TX_BUFFER_SIZE == 0
|
||||
|
||||
void MarlinSerial::write(const uint8_t c) {
|
||||
#if ENABLED(SERIAL_XON_XOFF)
|
||||
// Do a priority insertion of an XON/XOFF char, if needed.
|
||||
const uint8_t state = xon_xoff_state;
|
||||
if (!(state & XON_XOFF_CHAR_SENT)) {
|
||||
writeNoHandshake(state & XON_XOFF_CHAR_MASK);
|
||||
xon_xoff_state = state | XON_XOFF_CHAR_SENT;
|
||||
}
|
||||
#endif
|
||||
writeNoHandshake(c);
|
||||
}
|
||||
|
||||
void MarlinSerial::writeNoHandshake(const uint8_t c) {
|
||||
while (!(HWUART->UART_SR & UART_SR_TXRDY)) { sw_barrier(); };
|
||||
HWUART->UART_THR = c;
|
||||
}
|
||||
|
||||
#endif // TX_BUFFER_SIZE == 0
|
||||
|
||||
/**
|
||||
* Imports from print.h
|
||||
*/
|
||||
|
||||
void MarlinSerial::print(char c, int base) {
|
||||
print((long)c, base);
|
||||
}
|
||||
|
||||
void MarlinSerial::print(unsigned char b, int base) {
|
||||
print((unsigned long)b, base);
|
||||
}
|
||||
|
||||
void MarlinSerial::print(int n, int base) {
|
||||
print((long)n, base);
|
||||
}
|
||||
|
||||
void MarlinSerial::print(unsigned int n, int base) {
|
||||
print((unsigned long)n, base);
|
||||
}
|
||||
|
||||
void MarlinSerial::print(long n, int base) {
|
||||
if (base == 0)
|
||||
write(n);
|
||||
else if (base == 10) {
|
||||
if (n < 0) {
|
||||
print('-');
|
||||
n = -n;
|
||||
}
|
||||
printNumber(n, 10);
|
||||
}
|
||||
else
|
||||
printNumber(n, base);
|
||||
}
|
||||
|
||||
void MarlinSerial::print(unsigned long n, int base) {
|
||||
if (base == 0) write(n);
|
||||
else printNumber(n, base);
|
||||
}
|
||||
|
||||
void MarlinSerial::print(double n, int digits) {
|
||||
printFloat(n, digits);
|
||||
}
|
||||
|
||||
void MarlinSerial::println(void) {
|
||||
print('\r');
|
||||
print('\n');
|
||||
}
|
||||
|
||||
void MarlinSerial::println(const String& s) {
|
||||
print(s);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(const char c[]) {
|
||||
print(c);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(char c, int base) {
|
||||
print(c, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(unsigned char b, int base) {
|
||||
print(b, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(int n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(unsigned int n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(long n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(unsigned long n, int base) {
|
||||
print(n, base);
|
||||
println();
|
||||
}
|
||||
|
||||
void MarlinSerial::println(double n, int digits) {
|
||||
print(n, digits);
|
||||
println();
|
||||
}
|
||||
|
||||
// Private Methods
|
||||
|
||||
void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
|
||||
if (n) {
|
||||
unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
|
||||
int8_t i = 0;
|
||||
while (n) {
|
||||
buf[i++] = n % base;
|
||||
n /= base;
|
||||
}
|
||||
while (i--)
|
||||
print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
|
||||
}
|
||||
else
|
||||
print('0');
|
||||
}
|
||||
|
||||
void MarlinSerial::printFloat(double number, uint8_t digits) {
|
||||
// Handle negative numbers
|
||||
if (number < 0.0) {
|
||||
print('-');
|
||||
number = -number;
|
||||
}
|
||||
|
||||
// Round correctly so that print(1.999, 2) prints as "2.00"
|
||||
double rounding = 0.5;
|
||||
for (uint8_t i = 0; i < digits; ++i)
|
||||
rounding *= 0.1;
|
||||
|
||||
number += rounding;
|
||||
|
||||
// Extract the integer part of the number and print it
|
||||
unsigned long int_part = (unsigned long)number;
|
||||
double remainder = number - (double)int_part;
|
||||
print(int_part);
|
||||
|
||||
// Print the decimal point, but only if there are digits beyond
|
||||
if (digits) {
|
||||
print('.');
|
||||
// Extract digits from the remainder one at a time
|
||||
while (digits--) {
|
||||
remainder *= 10.0;
|
||||
int toPrint = int(remainder);
|
||||
print(toPrint);
|
||||
remainder -= toPrint;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Preinstantiate
|
||||
MarlinSerial customizedSerial;
|
||||
|
||||
#endif // ARDUINO_ARCH_SAM
|
142
Marlin/src/HAL/HAL_DUE/MarlinSerial_Due.h
Normal file
142
Marlin/src/HAL/HAL_DUE/MarlinSerial_Due.h
Normal file
|
@ -0,0 +1,142 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* MarlinSerial_Due.h - Hardware serial library for Arduino DUE
|
||||
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
|
||||
* Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
*/
|
||||
|
||||
#ifndef MARLINSERIAL_DUE_H
|
||||
#define MARLINSERIAL_DUE_H
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#include <WString.h>
|
||||
|
||||
#ifndef SERIAL_PORT
|
||||
#define SERIAL_PORT 0
|
||||
#endif
|
||||
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
#define BYTE 0
|
||||
|
||||
// Define constants and variables for buffering incoming serial data. We're
|
||||
// using a ring buffer (I think), in which rx_buffer_head is the index of the
|
||||
// location to which to write the next incoming character and rx_buffer_tail
|
||||
// is the index of the location from which to read.
|
||||
// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
|
||||
#ifndef RX_BUFFER_SIZE
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#ifndef TX_BUFFER_SIZE
|
||||
#define TX_BUFFER_SIZE 32
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
|
||||
#error "XON/XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
|
||||
#endif
|
||||
|
||||
#if !IS_POWER_OF_2(RX_BUFFER_SIZE) || RX_BUFFER_SIZE < 2
|
||||
#error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
|
||||
#endif
|
||||
|
||||
#if TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
|
||||
#error "TX_BUFFER_SIZE must be 0 or a power of 2 greater than 1."
|
||||
#endif
|
||||
|
||||
#if RX_BUFFER_SIZE > 256
|
||||
typedef uint16_t ring_buffer_pos_t;
|
||||
#else
|
||||
typedef uint8_t ring_buffer_pos_t;
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
extern uint8_t rx_dropped_bytes;
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
extern ring_buffer_pos_t rx_max_enqueued;
|
||||
#endif
|
||||
|
||||
class MarlinSerial {
|
||||
|
||||
public:
|
||||
MarlinSerial() {};
|
||||
static void begin(const long);
|
||||
static void end();
|
||||
static int peek(void);
|
||||
static int read(void);
|
||||
static void flush(void);
|
||||
static ring_buffer_pos_t available(void);
|
||||
static void checkRx(void);
|
||||
static void write(const uint8_t c);
|
||||
#if TX_BUFFER_SIZE > 0
|
||||
static uint8_t availableForWrite(void);
|
||||
static void flushTX(void);
|
||||
#endif
|
||||
static void writeNoHandshake(const uint8_t c);
|
||||
|
||||
#if ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
FORCE_INLINE static uint32_t dropped() { return rx_dropped_bytes; }
|
||||
#endif
|
||||
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return rx_max_enqueued; }
|
||||
#endif
|
||||
|
||||
static FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
|
||||
static FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
|
||||
static FORCE_INLINE void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
|
||||
static FORCE_INLINE void print(const char* str) { write(str); }
|
||||
|
||||
static void print(char, int = BYTE);
|
||||
static void print(unsigned char, int = BYTE);
|
||||
static void print(int, int = DEC);
|
||||
static void print(unsigned int, int = DEC);
|
||||
static void print(long, int = DEC);
|
||||
static void print(unsigned long, int = DEC);
|
||||
static void print(double, int = 2);
|
||||
|
||||
static void println(const String& s);
|
||||
static void println(const char[]);
|
||||
static void println(char, int = BYTE);
|
||||
static void println(unsigned char, int = BYTE);
|
||||
static void println(int, int = DEC);
|
||||
static void println(unsigned int, int = DEC);
|
||||
static void println(long, int = DEC);
|
||||
static void println(unsigned long, int = DEC);
|
||||
static void println(double, int = 2);
|
||||
static void println(void);
|
||||
operator bool() { return true; }
|
||||
|
||||
private:
|
||||
static void printNumber(unsigned long, const uint8_t);
|
||||
static void printFloat(double, uint8_t);
|
||||
};
|
||||
|
||||
extern MarlinSerial customizedSerial;
|
||||
|
||||
#endif // MARLINSERIAL_DUE_H
|
|
@ -81,14 +81,16 @@ void HAL_adc_init(void) {
|
|||
extern void kill(const char*);
|
||||
extern const char errormagic[];
|
||||
|
||||
void HAL_adc_enable_channel(int pin) {
|
||||
if (!WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) {
|
||||
MYSERIAL.printf("%sINVALID ANALOG PORT:%d\n", errormagic, pin);
|
||||
void HAL_adc_enable_channel(int ch) {
|
||||
pin_t pin = analogInputToDigitalPin(ch);
|
||||
|
||||
if (pin == -1) {
|
||||
MYSERIAL.printf("%sINVALID ANALOG PORT:%d\n", errormagic, ch);
|
||||
kill(MSG_KILLED);
|
||||
}
|
||||
|
||||
int8_t pin_port = adc_pin_map[pin].port,
|
||||
pin_port_pin = adc_pin_map[pin].pin,
|
||||
int8_t pin_port = LPC1768_PIN_PORT(pin),
|
||||
pin_port_pin = LPC1768_PIN_PIN(pin),
|
||||
pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
|
||||
uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 :
|
||||
pin_port == 0 ? 1 :
|
||||
|
@ -111,15 +113,16 @@ void HAL_adc_enable_channel(int pin) {
|
|||
}
|
||||
|
||||
uint8_t active_adc = 0;
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||
if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) {
|
||||
MYSERIAL.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
|
||||
void HAL_adc_start_conversion(const uint8_t ch) {
|
||||
if (analogInputToDigitalPin(ch) == -1) {
|
||||
MYSERIAL.printf("HAL: HAL_adc_start_conversion: invalid channel %d\n", ch);
|
||||
return;
|
||||
}
|
||||
LPC_ADC->ADCR &= ~0xFF; // Reset
|
||||
SBI(LPC_ADC->ADCR, adc_pin_map[adc_pin].adc); // Select Channel
|
||||
SBI(LPC_ADC->ADCR, 24); // Start conversion
|
||||
active_adc = adc_pin;
|
||||
|
||||
LPC_ADC->ADCR &= ~0xFF; // Reset
|
||||
SBI(LPC_ADC->ADCR, ch); // Select Channel
|
||||
SBI(LPC_ADC->ADCR, 24); // Start conversion
|
||||
active_adc = ch;
|
||||
}
|
||||
|
||||
bool HAL_adc_finished(void) {
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
#define HAL_TIMER_TYPE uint32_t
|
||||
typedef uint32_t timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
|
||||
|
||||
#define STEP_TIMER_NUM 0 // index of timer to use for stepper
|
||||
|
@ -77,7 +77,7 @@
|
|||
void HAL_timer_init(void);
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
|
||||
|
||||
static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const HAL_TIMER_TYPE count) {
|
||||
static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const timer_t count) {
|
||||
switch (timer_num) {
|
||||
case 0:
|
||||
LPC_TIM0->MR0 = count;
|
||||
|
@ -92,7 +92,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const HAL_
|
|||
}
|
||||
}
|
||||
|
||||
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
|
||||
static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||
switch (timer_num) {
|
||||
case 0: return LPC_TIM0->MR0;
|
||||
case 1: return LPC_TIM1->MR0;
|
||||
|
@ -100,7 +100,7 @@ static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(const uint8_t timer_num) {
|
||||
static FORCE_INLINE timer_t HAL_timer_get_current_count(const uint8_t timer_num) {
|
||||
switch (timer_num) {
|
||||
case 0: return LPC_TIM0->TC;
|
||||
case 1: return LPC_TIM1->TC;
|
||||
|
|
|
@ -102,7 +102,7 @@ void HardwareSerial::begin(uint32_t baudrate) {
|
|||
|
||||
// Initialize eripheral with given to corresponding parameter
|
||||
UART_Init(UARTx, &UARTConfigStruct);
|
||||
|
||||
|
||||
// Enable and reset the TX and RX FIFOs
|
||||
UART_FIFOConfigStructInit(&FIFOConfig);
|
||||
UART_FIFOConfig(UARTx, &FIFOConfig);
|
||||
|
@ -113,7 +113,7 @@ void HardwareSerial::begin(uint32_t baudrate) {
|
|||
// Configure Interrupts
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RLS, ENABLE);
|
||||
|
||||
|
||||
if (UARTx == LPC_UART0)
|
||||
NVIC_EnableIRQ(UART0_IRQn);
|
||||
else if ((LPC_UART1_TypeDef *) UARTx == LPC_UART1)
|
||||
|
@ -135,13 +135,13 @@ int HardwareSerial::peek() {
|
|||
/* Temporarily lock out UART receive interrupts during this read so the UART receive
|
||||
interrupt won't cause problems with the index values */
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
|
||||
|
||||
|
||||
if (RxQueueReadPos != RxQueueWritePos)
|
||||
byte = RxBuffer[RxQueueReadPos];
|
||||
|
||||
/* Re-enable UART interrupts */
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
|
||||
|
||||
return byte;
|
||||
}
|
||||
|
||||
|
@ -151,7 +151,7 @@ int HardwareSerial::read() {
|
|||
/* Temporarily lock out UART receive interrupts during this read so the UART receive
|
||||
interrupt won't cause problems with the index values */
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, DISABLE);
|
||||
|
||||
|
||||
if (RxQueueReadPos != RxQueueWritePos) {
|
||||
byte = RxBuffer[RxQueueReadPos];
|
||||
RxQueueReadPos = (RxQueueReadPos + 1) % RX_BUFFER_SIZE;
|
||||
|
@ -159,7 +159,7 @@ int HardwareSerial::read() {
|
|||
|
||||
/* Re-enable UART interrupts */
|
||||
UART_IntConfig(UARTx, UART_INTCFG_RBR, ENABLE);
|
||||
|
||||
|
||||
return byte;
|
||||
}
|
||||
|
||||
|
@ -170,7 +170,7 @@ size_t HardwareSerial::write(uint8_t send) {
|
|||
|
||||
/* If the Tx Buffer is full, wait for space to clear */
|
||||
if ((TxQueueWritePos+1) % TX_BUFFER_SIZE == TxQueueReadPos) flushTX();
|
||||
|
||||
|
||||
/* Temporarily lock out UART transmit interrupts during this read so the UART transmit interrupt won't
|
||||
cause problems with the index values */
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
|
||||
|
@ -180,7 +180,7 @@ size_t HardwareSerial::write(uint8_t send) {
|
|||
fifolvl = *(reinterpret_cast<volatile uint32_t *>(&((LPC_UART1_TypeDef *) UARTx)->FIFOLVL));
|
||||
else
|
||||
fifolvl = *(reinterpret_cast<volatile uint32_t *>(&UARTx->FIFOLVL));
|
||||
|
||||
|
||||
/* If the queue is empty and there's space in the FIFO, immediately send the byte */
|
||||
if (TxQueueWritePos == TxQueueReadPos && fifolvl < UART_TX_FIFO_SIZE) {
|
||||
bytes = UART_Send(UARTx, &send, 1, BLOCKING);
|
||||
|
@ -191,10 +191,10 @@ size_t HardwareSerial::write(uint8_t send) {
|
|||
TxQueueWritePos = (TxQueueWritePos+1) % TX_BUFFER_SIZE;
|
||||
bytes++;
|
||||
}
|
||||
|
||||
|
||||
/* Re-enable the TX Interrupt */
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, ENABLE);
|
||||
|
||||
|
||||
return bytes;
|
||||
#else
|
||||
return UART_Send(UARTx, &send, 1, BLOCKING);
|
||||
|
@ -251,7 +251,7 @@ void HardwareSerial::IRQHandler() {
|
|||
return;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if ( IIRValue == UART_IIR_INTID_RDA ) /* Receive Data Available */
|
||||
{
|
||||
/* Clear the FIFO */
|
||||
|
@ -278,7 +278,7 @@ void HardwareSerial::IRQHandler() {
|
|||
|
||||
/* Wait for FIFO buffer empty */
|
||||
while (UART_CheckBusy(UARTx) == SET);
|
||||
|
||||
|
||||
/* Transfer up to UART_TX_FIFO_SIZE bytes of data */
|
||||
for (int i = 0; i < UART_TX_FIFO_SIZE && TxQueueWritePos != TxQueueReadPos; i++) {
|
||||
/* Move a piece of data into the transmit FIFO */
|
||||
|
@ -287,7 +287,7 @@ void HardwareSerial::IRQHandler() {
|
|||
else
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
/* If there is no more data to send, disable the transmit interrupt - else enable it or keep it enabled */
|
||||
if (TxQueueWritePos == TxQueueReadPos)
|
||||
UART_IntConfig(UARTx, UART_INTCFG_THRE, DISABLE);
|
||||
|
|
509
Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp
Normal file
509
Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp
Normal file
|
@ -0,0 +1,509 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* The class Servo uses the PWM class to implement its functions
|
||||
*
|
||||
* All PWMs use the same repetition rate - 20mS because that's the normal servo rate
|
||||
*/
|
||||
|
||||
/**
|
||||
* This is a hybrid system.
|
||||
*
|
||||
* The PWM1 module is used to directly control the Servo 0, 1 & 3 pins. This keeps
|
||||
* the pulse width jitter to under a microsecond.
|
||||
*
|
||||
* For all other pins the PWM1 module is used to generate interrupts. The ISR
|
||||
* routine does the actual setting/clearing of pins. The upside is that any pin can
|
||||
* have a PWM channel assigned to it. The downside is that there is more pulse width
|
||||
* jitter. The jitter depends on what else is happening in the system and what ISRs
|
||||
* prempt the PWM ISR. Writing to the SD card can add 20 microseconds to the pulse
|
||||
* width.
|
||||
*/
|
||||
|
||||
/**
|
||||
* The data structures are setup to minimize the computation done by the ISR which
|
||||
* minimizes ISR execution time. Execution times are 2.2 - 3.7 microseconds.
|
||||
*
|
||||
* Two tables are used. active_table is used by the ISR. Changes to the table are
|
||||
* are done by copying the active_table into the work_table, updating the work_table
|
||||
* and then swapping the two tables. Swapping is done by manipulating pointers.
|
||||
*
|
||||
* Immediately after the swap the ISR uses the work_table until the start of the
|
||||
* next 20mS cycle. During this transition the "work_table" is actually the table
|
||||
* that was being used before the swap. The "active_table" contains the data that
|
||||
* will start being used at the start of the next 20mS period. This keeps the pins
|
||||
* well behaved during the transition.
|
||||
*
|
||||
* The ISR's priority is set to the maximum otherwise other ISRs can cause considerable
|
||||
* jitter in the PWM high time.
|
||||
*
|
||||
* See the end of this file for details on the hardware/firmware interaction
|
||||
*/
|
||||
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
#include <lpc17xx_pinsel.h>
|
||||
#include "LPC1768_PWM.h"
|
||||
#include "arduino.h"
|
||||
|
||||
#define NUM_PWMS 6
|
||||
|
||||
typedef struct { // holds all data needed to control/init one of the PWM channels
|
||||
uint8_t sequence; // 0: available slot, 1 - 6: PWM channel assigned to that slot
|
||||
pin_t pin;
|
||||
uint16_t PWM_mask; // MASK TO CHECK/WRITE THE IR REGISTER
|
||||
volatile uint32_t* set_register;
|
||||
volatile uint32_t* clr_register;
|
||||
uint32_t write_mask; // USED BY SET/CLEAR COMMANDS
|
||||
uint32_t microseconds; // value written to MR register
|
||||
uint32_t min; // lower value limit checked by WRITE routine before writing to the MR register
|
||||
uint32_t max; // upper value limit checked by WRITE routine before writing to the MR register
|
||||
bool PWM_flag; // 0 - USED BY sERVO, 1 - USED BY ANALOGWRITE
|
||||
uint8_t servo_index; // 0 - MAX_SERVO -1 : servo index, 0xFF : PWM channel
|
||||
bool active_flag; // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
|
||||
uint8_t assigned_MR; // Which MR (1-6) is used by this logical channel
|
||||
uint32_t PCR_bit; // PCR register bit to enable PWM1 control of this pin
|
||||
uint32_t PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control
|
||||
|
||||
} PWM_map;
|
||||
|
||||
|
||||
#define MICRO_MAX 0xffffffff
|
||||
|
||||
#define PWM_MAP_INIT_ROW {0, 0xff, 0, 0, 0, 0, MICRO_MAX, 0, 0, 0, 0, 0, 0, 0, 0}
|
||||
#define PWM_MAP_INIT {PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
};
|
||||
|
||||
PWM_map PWM1_map_A[NUM_PWMS] = PWM_MAP_INIT;
|
||||
PWM_map PWM1_map_B[NUM_PWMS] = PWM_MAP_INIT;
|
||||
|
||||
PWM_map *active_table = PWM1_map_A;
|
||||
PWM_map *work_table = PWM1_map_B;
|
||||
PWM_map *ISR_table;
|
||||
|
||||
|
||||
#define IR_BIT(p) (p >= 0 && p <= 3 ? p : p + 4 )
|
||||
#define COPY_ACTIVE_TABLE for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]
|
||||
#define PIN_IS_INVERTED(p) 0 // place holder in case inverting PWM output is offered
|
||||
|
||||
|
||||
/**
|
||||
* Prescale register and MR0 register values
|
||||
*
|
||||
* 100MHz PCLK 50MHz PCLK 25MHz PCLK 12.5MHz PCLK
|
||||
* ----------------- ----------------- ----------------- -----------------
|
||||
* desired prescale MR0 prescale MR0 prescale MR0 prescale MR0 resolution
|
||||
* prescale register register register register register register register register in degrees
|
||||
* freq value value value value value value value value
|
||||
*
|
||||
* 8 11.5 159,999 5.25 159,999 2.13 159,999 0.5625 159,999 0.023
|
||||
* 4 24 79,999 11.5 79,999 5.25 79,999 2.125 79,999 0.045
|
||||
* 2 49 39,999 24 39,999 11.5 39,999 5.25 39,999 0.090
|
||||
* 1 99 19,999 49 19,999 24 19,999 11.5 19,999 0.180
|
||||
* 0.5 199 9,999 99 9,999 49 9,999 24 9,999 0.360
|
||||
* 0.25 399 4,999 199 4,999 99 4,999 49 4,999 0.720
|
||||
* 0.125 799 2,499 399 2,499 199 2,499 99 2,499 1.440
|
||||
*
|
||||
* The desired prescale frequency comes from an input in the range of 544 - 2400 microseconds and the
|
||||
* desire to just shift the input left or right as needed.
|
||||
*
|
||||
* A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
|
||||
* It also means we don't need to scale the input.
|
||||
*
|
||||
* The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
|
||||
* MR0 registers.
|
||||
*
|
||||
* Final settings:
|
||||
* PCLKSEL0: 0x0
|
||||
* PWM1PR: 0x018 (24)
|
||||
* PWM1MR0: 0x04E1F (19,999)
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
void LPC1768_PWM_init(void) {
|
||||
#define SBIT_CNTEN 0 // PWM1 counter & pre-scaler enable/disable
|
||||
#define SBIT_CNTRST 1 // reset counters to known state
|
||||
#define SBIT_PWMEN 3 // 1 - PWM, 0 - timer
|
||||
#define SBIT_PWMMR0R 1
|
||||
#define PCPWM1 6
|
||||
#define PCLK_PWM1 12
|
||||
|
||||
LPC_SC->PCONP |= (1 << PCPWM1); // enable PWM1 controller (enabled on power up)
|
||||
LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
|
||||
LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
|
||||
LPC_PWM1->MR0 = LPC_PWM1_MR0; // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
|
||||
// MR0 must be set before TCR enables the PWM
|
||||
LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST)| _BV(SBIT_PWMEN);; // enable counters, reset counters, set mode to PWM
|
||||
LPC_PWM1->TCR &= ~(_BV(SBIT_CNTRST)); // take counters out of reset
|
||||
LPC_PWM1->PR = LPC_PWM1_PR;
|
||||
LPC_PWM1->MCR = (_BV(SBIT_PWMMR0R) | _BV(0)); // Reset TC if it matches MR0, disable all interrupts except for MR0
|
||||
LPC_PWM1->CTCR = 0; // disable counter mode (enable PWM mode)
|
||||
|
||||
LPC_PWM1->LER = 0x07F; // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
|
||||
// Set all PWMs to single edge
|
||||
LPC_PWM1->PCR = 0; // single edge mode for all channels, PWM1 control of outputs off
|
||||
|
||||
NVIC_EnableIRQ(PWM1_IRQn); // Enable interrupt handler
|
||||
// NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module
|
||||
NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 0, 0)); // minimizes jitter due to higher priority ISRs
|
||||
}
|
||||
|
||||
|
||||
bool PWM_table_swap = false; // flag to tell the ISR that the tables have been swapped
|
||||
bool PWM_MR0_wait = false; // flag to ensure don't delay MR0 interrupt
|
||||
|
||||
|
||||
bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min /* = 1 */, uint32_t max /* = (LPC_PWM1_MR0 - MR0_MARGIN) */, uint8_t servo_index /* = 0xff */) {
|
||||
while (PWM_table_swap) delay(5); // don't do anything until the previous change has been implemented by the ISR
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
uint8_t slot = 0;
|
||||
for (uint8_t i = 0; i < NUM_PWMS ; i++) // see if already in table
|
||||
if (work_table[i].pin == pin) return 1;
|
||||
|
||||
for (uint8_t i = 1; (i < NUM_PWMS + 1) && !slot; i++) // find empty slot
|
||||
if ( !(work_table[i - 1].set_register)) slot = i; // any item that can't be zero when active or just attached is OK
|
||||
if (!slot) return 0;
|
||||
slot--; // turn it into array index
|
||||
|
||||
work_table[slot].pin = pin; // init slot
|
||||
work_table[slot].PWM_mask = 0; // real value set by PWM_write
|
||||
work_table[slot].set_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR : &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET;
|
||||
work_table[slot].clr_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET : &LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR;
|
||||
work_table[slot].write_mask = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
work_table[slot].microseconds = MICRO_MAX;
|
||||
work_table[slot].min = min;
|
||||
work_table[slot].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
work_table[slot].servo_index = servo_index;
|
||||
work_table[slot].active_flag = false;
|
||||
|
||||
//swap tables
|
||||
PWM_MR0_wait = true;
|
||||
while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it.
|
||||
|
||||
NVIC_DisableIRQ(PWM1_IRQn);
|
||||
PWM_map *pointer_swap = active_table;
|
||||
active_table = work_table;
|
||||
work_table = pointer_swap;
|
||||
PWM_table_swap = true; // tell the ISR that the tables have been swapped
|
||||
NVIC_EnableIRQ(PWM1_IRQn); // re-enable PWM interrupts
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
#define pin_11_PWM_channel 2
|
||||
#define pin_6_PWM_channel 3
|
||||
#define pin_4_PWM_channel 1
|
||||
|
||||
// used to keep track of which Match Registers have been used and if they will be used by the
|
||||
// PWM1 module to directly control the pin or will be used to generate an interrupt
|
||||
typedef struct { // status of PWM1 channel
|
||||
uint8_t map_used; // 0 - this MR register not used/assigned
|
||||
uint8_t map_PWM_INT; // 0 - available for interrupts, 1 - in use by PWM
|
||||
pin_t map_PWM_PIN; // pin for this PwM1 controlled pin / port
|
||||
volatile uint32_t* MR_register; // address of the MR register for this PWM1 channel
|
||||
uint32_t PCR_bit; // PCR register bit to enable PWM1 control of this pin
|
||||
uint32_t PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control
|
||||
} MR_map;
|
||||
|
||||
MR_map map_MR[NUM_PWMS];
|
||||
|
||||
void LPC1768_PWM_update_map_MR(void) {
|
||||
map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel) ? 1 : 0), 4, &LPC_PWM1->MR1, 0, 0};
|
||||
map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
|
||||
map_MR[2] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_6_PWM_channel) ? 1 : 0), 6, &LPC_PWM1->MR3, 0, 0};
|
||||
map_MR[3] = {0, 0, 0, &LPC_PWM1->MR4, 0, 0};
|
||||
map_MR[4] = {0, 0, 0, &LPC_PWM1->MR5, 0, 0};
|
||||
map_MR[5] = {0, 0, 0, &LPC_PWM1->MR6, 0, 0};
|
||||
}
|
||||
|
||||
|
||||
uint32_t LPC1768_PWM_interrupt_mask = 1;
|
||||
|
||||
void LPC1768_PWM_update(void) {
|
||||
for (uint8_t i = NUM_PWMS; --i;) { // (bubble) sort table by microseconds
|
||||
bool didSwap = false;
|
||||
PWM_map temp;
|
||||
for (uint16_t j = 0; j < i; ++j) {
|
||||
if (work_table[j].microseconds > work_table[j + 1].microseconds) {
|
||||
temp = work_table[j + 1];
|
||||
work_table[j + 1] = work_table[j];
|
||||
work_table[j] = temp;
|
||||
didSwap = true;
|
||||
}
|
||||
}
|
||||
if (!didSwap) break;
|
||||
}
|
||||
|
||||
LPC1768_PWM_interrupt_mask = 0; // set match registers to new values, build IRQ mask
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) {
|
||||
if (work_table[i].active_flag == true) {
|
||||
work_table[i].sequence = i + 1;
|
||||
|
||||
// first see if there is a PWM1 controlled pin for this entry
|
||||
bool found = false;
|
||||
for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {
|
||||
if ( (map_MR[j].map_PWM_PIN == work_table[i].pin) && map_MR[j].map_PWM_INT ) {
|
||||
*map_MR[j].MR_register = work_table[i].microseconds; // found one of the PWM pins
|
||||
work_table[i].PWM_mask = 0;
|
||||
work_table[i].PCR_bit = map_MR[j].PCR_bit; // PCR register bit to enable PWM1 control of this pin
|
||||
work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control} MR_map;
|
||||
map_MR[j].map_used = 2;
|
||||
work_table[i].assigned_MR = j +1; // only used to help in debugging
|
||||
found = true;
|
||||
}
|
||||
}
|
||||
|
||||
// didn't find a PWM1 pin so get an interrupt
|
||||
for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
|
||||
if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
|
||||
*map_MR[k].MR_register = work_table[i].microseconds; // found one for an interrupt pin
|
||||
map_MR[k].map_used = 1;
|
||||
LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1)); // set bit in the MCR to enable this MR to generate an interrupt
|
||||
work_table[i].PWM_mask = _BV(IR_BIT(k + 1)); // bit in the IR that will go active when this MR generates an interrupt
|
||||
work_table[i].assigned_MR = k +1; // only used to help in debugging
|
||||
found = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
work_table[i].sequence = 0;
|
||||
}
|
||||
LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0); // add in MR0 interrupt
|
||||
|
||||
// swap tables
|
||||
|
||||
PWM_MR0_wait = true;
|
||||
while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it.
|
||||
|
||||
NVIC_DisableIRQ(PWM1_IRQn);
|
||||
LPC_PWM1->LER = 0x07E; // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
|
||||
PWM_map *pointer_swap = active_table;
|
||||
active_table = work_table;
|
||||
work_table = pointer_swap;
|
||||
PWM_table_swap = true; // tell the ISR that the tables have been swapped
|
||||
NVIC_EnableIRQ(PWM1_IRQn); // re-enable PWM interrupts
|
||||
}
|
||||
|
||||
|
||||
bool LPC1768_PWM_write(pin_t pin, uint32_t value) {
|
||||
while (PWM_table_swap) delay(5); // don't do anything until the previous change has been implemented by the ISR
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // find slot
|
||||
if (work_table[i].pin == pin) slot = i;
|
||||
if (slot == 0xFF) return false; // return error if pin not found
|
||||
|
||||
LPC1768_PWM_update_map_MR();
|
||||
|
||||
switch(pin) {
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel); // enable PWM1 module control of this pin
|
||||
map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM
|
||||
map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0x2 << 8; // ISR must do this AFTER setting PCR
|
||||
break;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
map_MR[pin_6_PWM_channel - 1].PCR_bit = _BV(8 + pin_6_PWM_channel); // enable PWM1 module control of this pin
|
||||
map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM
|
||||
map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10; // ISR must do this AFTER setting PCR
|
||||
break;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel); // enable PWM1 module control of this pin
|
||||
map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM
|
||||
map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0x2 << 4; // ISR must do this AFTER setting PCR
|
||||
break;
|
||||
default: // ISR pins
|
||||
pinMode(pin, OUTPUT); // set pin to output but don't write anything in case it's already in use
|
||||
break;
|
||||
}
|
||||
|
||||
work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
|
||||
work_table[slot].active_flag = true;
|
||||
|
||||
LPC1768_PWM_update();
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool LPC1768_PWM_detach_pin(pin_t pin) {
|
||||
while (PWM_table_swap) delay(5); // don't do anything until the previous change has been implemented by the ISR
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // find slot
|
||||
if (work_table[i].pin == pin) slot = i;
|
||||
if (slot == 0xFF) return false; // return error if pin not found
|
||||
|
||||
LPC1768_PWM_update_map_MR();
|
||||
|
||||
// OK to make these changes before the MR0 interrupt
|
||||
switch(pin) {
|
||||
case P1_20: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
LPC_PWM1->PCR &= ~(_BV(8 + pin_11_PWM_channel)); // disable PWM1 module control of this pin
|
||||
map_MR[pin_11_PWM_channel - 1].PCR_bit = 0;
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 8); // return pin to general purpose I/O
|
||||
map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0;
|
||||
map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
|
||||
break;
|
||||
case P1_21: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
LPC_PWM1->PCR &= ~(_BV(8 + pin_6_PWM_channel)); // disable PWM1 module control of this pin
|
||||
map_MR[pin_6_PWM_channel - 1].PCR_bit = 0;
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 10); // return pin to general purpose I/O
|
||||
map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0;
|
||||
map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
|
||||
break;
|
||||
case P1_18: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel)); // disable PWM1 module control of this pin
|
||||
map_MR[pin_4_PWM_channel - 1].PCR_bit = 0;
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 4); // return pin to general purpose I/O
|
||||
map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0;
|
||||
map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
|
||||
break;
|
||||
}
|
||||
|
||||
pinMode(pin, INPUT);
|
||||
|
||||
work_table[slot] = PWM_MAP_INIT_ROW;
|
||||
|
||||
LPC1768_PWM_update();
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool useable_hardware_PWM(pin_t pin) {
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // see if it's already setup
|
||||
if (work_table[i].pin == pin && work_table[i].sequence) return true;
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // see if there is an empty slot
|
||||
if (!work_table[i].sequence) return true;
|
||||
return false; // only get here if neither the above are true
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#define HAL_PWM_LPC1768_ISR extern "C" void PWM1_IRQHandler(void)
|
||||
|
||||
|
||||
// Both loops could be terminated when the last active channel is found but that would
|
||||
// result in variations ISR run time which results in variations in pulse width
|
||||
|
||||
/**
|
||||
* Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
|
||||
* the wrong pin may be toggled or even have the system hang.
|
||||
*/
|
||||
|
||||
|
||||
HAL_PWM_LPC1768_ISR {
|
||||
if (PWM_table_swap) ISR_table = work_table; // use old table if a swap was just done
|
||||
else ISR_table = active_table;
|
||||
|
||||
if (LPC_PWM1->IR & 0x1) { // MR0 interrupt
|
||||
ISR_table = active_table; // MR0 means new values could have been loaded so set everything
|
||||
if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
|
||||
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) {
|
||||
if(ISR_table[i].active_flag && !((ISR_table[i].pin == P1_20) ||
|
||||
(ISR_table[i].pin == P1_21) ||
|
||||
(ISR_table[i].pin == P1_18)))
|
||||
*ISR_table[i].set_register = ISR_table[i].write_mask; // set pins for all enabled interrupt channels active
|
||||
if (PWM_table_swap && ISR_table[i].PCR_bit) {
|
||||
LPC_PWM1->PCR |= ISR_table[i].PCR_bit; // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits; // set pin mode to PWM1 control - must be done after PCR
|
||||
}
|
||||
}
|
||||
PWM_table_swap = false;
|
||||
PWM_MR0_wait = false;
|
||||
LPC_PWM1->IR = 0x01; // clear the MR0 interrupt flag bit
|
||||
}
|
||||
else {
|
||||
for (uint8_t i = 0; i < NUM_PWMS ; i++)
|
||||
if (ISR_table[i].active_flag && (LPC_PWM1->IR & ISR_table[i].PWM_mask) ){
|
||||
LPC_PWM1->IR = ISR_table[i].PWM_mask; // clear the interrupt flag bits for expected interrupts
|
||||
*ISR_table[i].clr_register = ISR_table[i].write_mask; // set channel to inactive
|
||||
}
|
||||
}
|
||||
|
||||
LPC_PWM1->IR = 0x70F; // guarantees all interrupt flags are cleared which, if there is an unexpected
|
||||
// PWM interrupt, will keep the ISR from hanging which will crash the controller
|
||||
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
///////////////// HARDWARE FIRMWARE INTERACTION ////////////////
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
/**
|
||||
* Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
|
||||
* interrupt. The only exception is detaching pins. It doesn't matter when they go
|
||||
* tristate.
|
||||
*
|
||||
* The LPC1768_PWM_init routine kicks off the MR0 interrupt. This interrupt is never disabled or
|
||||
* delayed.
|
||||
*
|
||||
* The PWM_table_swap flag is set when the firmware has swapped in an updated table. It is
|
||||
* cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
|
||||
* It serves two purposes:
|
||||
* 1) Tells the ISR that the tables have been swapped
|
||||
* 2) Keeps the firmware from starting a new update until the previous one has been completed.
|
||||
*
|
||||
* The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
|
||||
* the ISR during the MR0 interrupt. It is used to avoid delaying the MR0 interrupt when swapping in
|
||||
* an updated table. This avoids glitches in pulse width and/or repetition rate.
|
||||
*
|
||||
* The sequence of events during a write to a PWM channel is:
|
||||
* 1) Waits until PWM_table_swap flag is false before starting
|
||||
* 2) Copies the active table into the work table
|
||||
* 3) Updates the work table
|
||||
* NOTES - MR1-MR6 are updated at this time. The updates aren't put into use until the first
|
||||
* MR0 after the LER register has been written. The LER register is written during the
|
||||
* table swap process.
|
||||
* - The MCR mask is created at this time. It is not used until the ISR writes the MCR
|
||||
* during the MR0 interrupt in the table swap process.
|
||||
* 4) Sets the PWM_MR0_wait flag
|
||||
* 5) ISR clears the PWM_MR0_wait flag during the next MR0 interrupt
|
||||
* 6) Once the PWM_MR0_wait flag is cleared then the firmware:
|
||||
* disables the ISR interrupt
|
||||
* swaps the pointers to the tables
|
||||
* writes to the LER register
|
||||
* sets the PWM_table_swap flag active
|
||||
* re-enables the ISR
|
||||
* 7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
|
||||
* unmodified, active table.
|
||||
* 8) On the next MR0 interrupt the ISR:
|
||||
* switches over to the active table
|
||||
* clears the PWM_table_swap and PWM_MR0_wait flags
|
||||
* updates the MCR register with the possibly new interrupt sources/assignments
|
||||
* writes to the PCR register to enable the direct control of the Servo 0, 1 & 3 pins by the PWM1 module
|
||||
* sets the PINSEL3 register to function/mode 0x2 for the Servo 0, 1 & 3 pins
|
||||
* NOTE - PCR must be set before PINSEL
|
||||
* sets the pins controlled by the ISR to their active states
|
||||
*/
|
||||
|
|
@ -60,88 +60,7 @@
|
|||
* See the end of this file for details on the hardware/firmware interaction
|
||||
*/
|
||||
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
#include <lpc17xx_pinsel.h>
|
||||
|
||||
#define NUM_PWMS 6
|
||||
|
||||
typedef struct { // holds all data needed to control/init one of the PWM channels
|
||||
uint8_t sequence; // 0: available slot, 1 - 6: PWM channel assigned to that slot
|
||||
uint8_t logical_pin;
|
||||
uint16_t PWM_mask; // MASK TO CHECK/WRITE THE IR REGISTER
|
||||
volatile uint32_t* set_register;
|
||||
volatile uint32_t* clr_register;
|
||||
uint32_t write_mask; // USED BY SET/CLEAR COMMANDS
|
||||
uint32_t microseconds; // value written to MR register
|
||||
uint32_t min; // lower value limit checked by WRITE routine before writing to the MR register
|
||||
uint32_t max; // upper value limit checked by WRITE routine before writing to the MR register
|
||||
bool PWM_flag; // 0 - USED BY sERVO, 1 - USED BY ANALOGWRITE
|
||||
uint8_t servo_index; // 0 - MAX_SERVO -1 : servo index, 0xFF : PWM channel
|
||||
bool active_flag; // THIS TABLE ENTRY IS ACTIVELY TOGGLING A PIN
|
||||
uint8_t assigned_MR; // Which MR (1-6) is used by this logical channel
|
||||
uint32_t PCR_bit; // PCR register bit to enable PWM1 control of this pin
|
||||
uint32_t PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control
|
||||
|
||||
} PWM_map;
|
||||
|
||||
|
||||
#define MICRO_MAX 0xffffffff
|
||||
|
||||
#define PWM_MAP_INIT_ROW {0, 0xff, 0, 0, 0, 0, MICRO_MAX, 0, 0, 0, 0, 0, 0, 0, 0}
|
||||
#define PWM_MAP_INIT {PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
PWM_MAP_INIT_ROW,\
|
||||
};
|
||||
|
||||
PWM_map PWM1_map_A[NUM_PWMS] = PWM_MAP_INIT;
|
||||
PWM_map PWM1_map_B[NUM_PWMS] = PWM_MAP_INIT;
|
||||
|
||||
PWM_map *active_table = PWM1_map_A;
|
||||
PWM_map *work_table = PWM1_map_B;
|
||||
PWM_map *ISR_table;
|
||||
|
||||
|
||||
#define IR_BIT(p) (p >= 0 && p <= 3 ? p : p + 4 )
|
||||
#define COPY_ACTIVE_TABLE for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]
|
||||
#define PIN_IS_INVERTED(p) 0 // place holder in case inverting PWM output is offered
|
||||
|
||||
|
||||
/**
|
||||
* Prescale register and MR0 register values
|
||||
*
|
||||
* 100MHz PCLK 50MHz PCLK 25MHz PCLK 12.5MHz PCLK
|
||||
* ----------------- ----------------- ----------------- -----------------
|
||||
* desired prescale MR0 prescale MR0 prescale MR0 prescale MR0 resolution
|
||||
* prescale register register register register register register register register in degrees
|
||||
* freq value value value value value value value value
|
||||
*
|
||||
* 8 11.5 159,999 5.25 159,999 2.13 159,999 0.5625 159,999 0.023
|
||||
* 4 24 79,999 11.5 79,999 5.25 79,999 2.125 79,999 0.045
|
||||
* 2 49 39,999 24 39,999 11.5 39,999 5.25 39,999 0.090
|
||||
* 1 99 19,999 49 19,999 24 19,999 11.5 19,999 0.180
|
||||
* 0.5 199 9,999 99 9,999 49 9,999 24 9,999 0.360
|
||||
* 0.25 399 4,999 199 4,999 99 4,999 49 4,999 0.720
|
||||
* 0.125 799 2,499 399 2,499 199 2,499 99 2,499 1.440
|
||||
*
|
||||
* The desired prescale frequency comes from an input in the range of 544 - 2400 microseconds and the
|
||||
* desire to just shift the input left or right as needed.
|
||||
*
|
||||
* A resolution of 0.2 degrees seems reasonable so a prescale frequency output of 1MHz is being used.
|
||||
* It also means we don't need to scale the input.
|
||||
*
|
||||
* The PCLK is set to 25MHz because that's the slowest one that gives whole numbers for prescale and
|
||||
* MR0 registers.
|
||||
*
|
||||
* Final settings:
|
||||
* PCLKSEL0: 0x0
|
||||
* PWM1PR: 0x018 (24)
|
||||
* PWM1MR0: 0x04E1F (19,999)
|
||||
*
|
||||
*/
|
||||
#include "fastio.h"
|
||||
|
||||
#define LPC_PWM1_MR0 19999 // base repetition rate minus one count - 20mS
|
||||
#define LPC_PWM1_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output
|
||||
|
@ -149,365 +68,10 @@ PWM_map *ISR_table;
|
|||
// 0: 25MHz, 1: 100MHz, 2: 50MHz, 3: 12.5MHZ to PWM1 prescaler
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
|
||||
void LPC1768_PWM_init(void) {
|
||||
#define SBIT_CNTEN 0 // PWM1 counter & pre-scaler enable/disable
|
||||
#define SBIT_CNTRST 1 // reset counters to known state
|
||||
#define SBIT_PWMEN 3 // 1 - PWM, 0 - timer
|
||||
#define SBIT_PWMMR0R 1
|
||||
#define PCPWM1 6
|
||||
#define PCLK_PWM1 12
|
||||
|
||||
LPC_SC->PCONP |= (1 << PCPWM1); // enable PWM1 controller (enabled on power up)
|
||||
LPC_SC->PCLKSEL0 &= ~(0x3 << PCLK_PWM1);
|
||||
LPC_SC->PCLKSEL0 |= (LPC_PWM1_PCLKSEL0 << PCLK_PWM1);
|
||||
LPC_PWM1->MR0 = LPC_PWM1_MR0; // TC resets every 19,999 + 1 cycles - sets PWM cycle(Ton+Toff) to 20 mS
|
||||
// MR0 must be set before TCR enables the PWM
|
||||
LPC_PWM1->TCR = _BV(SBIT_CNTEN) | _BV(SBIT_CNTRST)| _BV(SBIT_PWMEN);; // enable counters, reset counters, set mode to PWM
|
||||
LPC_PWM1->TCR &= ~(_BV(SBIT_CNTRST)); // take counters out of reset
|
||||
LPC_PWM1->PR = LPC_PWM1_PR;
|
||||
LPC_PWM1->MCR = (_BV(SBIT_PWMMR0R) | _BV(0)); // Reset TC if it matches MR0, disable all interrupts except for MR0
|
||||
LPC_PWM1->CTCR = 0; // disable counter mode (enable PWM mode)
|
||||
|
||||
LPC_PWM1->LER = 0x07F; // Set the latch Enable Bits to load the new Match Values for MR0 - MR6
|
||||
// Set all PWMs to single edge
|
||||
LPC_PWM1->PCR = 0; // single edge mode for all channels, PWM1 control of outputs off
|
||||
|
||||
NVIC_EnableIRQ(PWM1_IRQn); // Enable interrupt handler
|
||||
// NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module
|
||||
NVIC_SetPriority(PWM1_IRQn, NVIC_EncodePriority(0, 0, 0)); // minimizes jitter due to higher priority ISRs
|
||||
}
|
||||
|
||||
|
||||
bool PWM_table_swap = false; // flag to tell the ISR that the tables have been swapped
|
||||
bool PWM_MR0_wait = false; // flag to ensure don't delay MR0 interrupt
|
||||
|
||||
|
||||
bool LPC1768_PWM_attach_pin(uint8_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff) {
|
||||
while (PWM_table_swap) delay(5); // don't do anything until the previous change has been implemented by the ISR
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
uint8_t slot = 0;
|
||||
for (uint8_t i = 0; i < NUM_PWMS ; i++) // see if already in table
|
||||
if (work_table[i].logical_pin == pin) return 1;
|
||||
|
||||
for (uint8_t i = 1; (i < NUM_PWMS + 1) && !slot; i++) // find empty slot
|
||||
if ( !(work_table[i - 1].set_register)) slot = i; // any item that can't be zero when active or just attached is OK
|
||||
if (!slot) return 0;
|
||||
slot--; // turn it into array index
|
||||
|
||||
work_table[slot].logical_pin = pin; // init slot
|
||||
work_table[slot].PWM_mask = 0; // real value set by PWM_write
|
||||
work_table[slot].set_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(pin_map[pin].port)->FIOCLR : &LPC_GPIO(pin_map[pin].port)->FIOSET;
|
||||
work_table[slot].clr_register = PIN_IS_INVERTED(pin) ? &LPC_GPIO(pin_map[pin].port)->FIOSET : &LPC_GPIO(pin_map[pin].port)->FIOCLR;
|
||||
work_table[slot].write_mask = LPC_PIN(pin_map[pin].pin);
|
||||
work_table[slot].microseconds = MICRO_MAX;
|
||||
work_table[slot].min = min;
|
||||
work_table[slot].max = MIN(max, LPC_PWM1_MR0 - MR0_MARGIN);
|
||||
work_table[slot].servo_index = servo_index;
|
||||
work_table[slot].active_flag = false;
|
||||
|
||||
//swap tables
|
||||
PWM_MR0_wait = true;
|
||||
while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it.
|
||||
|
||||
NVIC_DisableIRQ(PWM1_IRQn);
|
||||
PWM_map *pointer_swap = active_table;
|
||||
active_table = work_table;
|
||||
work_table = pointer_swap;
|
||||
PWM_table_swap = true; // tell the ISR that the tables have been swapped
|
||||
NVIC_EnableIRQ(PWM1_IRQn); // re-enable PWM interrupts
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
#define pin_11_PWM_channel 2
|
||||
#define pin_6_PWM_channel 3
|
||||
#define pin_4_PWM_channel 1
|
||||
|
||||
// used to keep track of which Match Registers have been used and if they will be used by the
|
||||
// PWM1 module to directly control the pin or will be used to generate an interrupt
|
||||
typedef struct { // status of PWM1 channel
|
||||
uint8_t map_used; // 0 - this MR register not used/assigned
|
||||
uint8_t map_PWM_INT; // 0 - available for interrupts, 1 - in use by PWM
|
||||
uint8_t map_PWM_PIN; // logical pin number for this PwM1 controlled pin / port
|
||||
volatile uint32_t* MR_register; // address of the MR register for this PWM1 channel
|
||||
uint32_t PCR_bit; // PCR register bit to enable PWM1 control of this pin
|
||||
uint32_t PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control
|
||||
} MR_map;
|
||||
|
||||
MR_map map_MR[NUM_PWMS];
|
||||
|
||||
void LPC1768_PWM_update_map_MR(void) {
|
||||
map_MR[0] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_4_PWM_channel) ? 1 : 0), 4, &LPC_PWM1->MR1, 0, 0};
|
||||
map_MR[1] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_11_PWM_channel) ? 1 : 0), 11, &LPC_PWM1->MR2, 0, 0};
|
||||
map_MR[2] = {0, (uint8_t) (LPC_PWM1->PCR & _BV(8 + pin_6_PWM_channel) ? 1 : 0), 6, &LPC_PWM1->MR3, 0, 0};
|
||||
map_MR[3] = {0, 0, 0, &LPC_PWM1->MR4, 0, 0};
|
||||
map_MR[4] = {0, 0, 0, &LPC_PWM1->MR5, 0, 0};
|
||||
map_MR[5] = {0, 0, 0, &LPC_PWM1->MR6, 0, 0};
|
||||
}
|
||||
|
||||
|
||||
uint32_t LPC1768_PWM_interrupt_mask = 1;
|
||||
|
||||
void LPC1768_PWM_update(void) {
|
||||
for (uint8_t i = NUM_PWMS; --i;) { // (bubble) sort table by microseconds
|
||||
bool didSwap = false;
|
||||
PWM_map temp;
|
||||
for (uint16_t j = 0; j < i; ++j) {
|
||||
if (work_table[j].microseconds > work_table[j + 1].microseconds) {
|
||||
temp = work_table[j + 1];
|
||||
work_table[j + 1] = work_table[j];
|
||||
work_table[j] = temp;
|
||||
didSwap = true;
|
||||
}
|
||||
}
|
||||
if (!didSwap) break;
|
||||
}
|
||||
|
||||
LPC1768_PWM_interrupt_mask = 0; // set match registers to new values, build IRQ mask
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) {
|
||||
if (work_table[i].active_flag == true) {
|
||||
work_table[i].sequence = i + 1;
|
||||
|
||||
// first see if there is a PWM1 controlled pin for this entry
|
||||
bool found = false;
|
||||
for (uint8_t j = 0; (j < NUM_PWMS) && !found; j++) {
|
||||
if ( (map_MR[j].map_PWM_PIN == work_table[i].logical_pin) && map_MR[j].map_PWM_INT ) {
|
||||
*map_MR[j].MR_register = work_table[i].microseconds; // found one of the PWM pins
|
||||
work_table[i].PWM_mask = 0;
|
||||
work_table[i].PCR_bit = map_MR[j].PCR_bit; // PCR register bit to enable PWM1 control of this pin
|
||||
work_table[i].PINSEL3_bits = map_MR[j].PINSEL3_bits; // PINSEL3 register bits to set pin mode to PWM1 control} MR_map;
|
||||
map_MR[j].map_used = 2;
|
||||
work_table[i].assigned_MR = j +1; // only used to help in debugging
|
||||
found = true;
|
||||
}
|
||||
}
|
||||
|
||||
// didn't find a PWM1 pin so get an interrupt
|
||||
for (uint8_t k = 0; (k < NUM_PWMS) && !found; k++) {
|
||||
if ( !(map_MR[k].map_PWM_INT || map_MR[k].map_used)) {
|
||||
*map_MR[k].MR_register = work_table[i].microseconds; // found one for an interrupt pin
|
||||
map_MR[k].map_used = 1;
|
||||
LPC1768_PWM_interrupt_mask |= _BV(3 * (k + 1)); // set bit in the MCR to enable this MR to generate an interrupt
|
||||
work_table[i].PWM_mask = _BV(IR_BIT(k + 1)); // bit in the IR that will go active when this MR generates an interrupt
|
||||
work_table[i].assigned_MR = k +1; // only used to help in debugging
|
||||
found = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
work_table[i].sequence = 0;
|
||||
}
|
||||
LPC1768_PWM_interrupt_mask |= (uint32_t) _BV(0); // add in MR0 interrupt
|
||||
|
||||
// swap tables
|
||||
|
||||
PWM_MR0_wait = true;
|
||||
while (PWM_MR0_wait) delay(5); //wait until MR0 interrupt has happend so don't delay it.
|
||||
|
||||
NVIC_DisableIRQ(PWM1_IRQn);
|
||||
LPC_PWM1->LER = 0x07E; // Set the latch Enable Bits to load the new Match Values for MR1 - MR6
|
||||
PWM_map *pointer_swap = active_table;
|
||||
active_table = work_table;
|
||||
work_table = pointer_swap;
|
||||
PWM_table_swap = true; // tell the ISR that the tables have been swapped
|
||||
NVIC_EnableIRQ(PWM1_IRQn); // re-enable PWM interrupts
|
||||
}
|
||||
|
||||
|
||||
bool LPC1768_PWM_write(uint8_t pin, uint32_t value) {
|
||||
while (PWM_table_swap) delay(5); // don't do anything until the previous change has been implemented by the ISR
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // find slot
|
||||
if (work_table[i].logical_pin == pin) slot = i;
|
||||
if (slot == 0xFF) return false; // return error if pin not found
|
||||
|
||||
LPC1768_PWM_update_map_MR();
|
||||
|
||||
switch(pin) {
|
||||
case 11: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
map_MR[pin_11_PWM_channel - 1].PCR_bit = _BV(8 + pin_11_PWM_channel); // enable PWM1 module control of this pin
|
||||
map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM
|
||||
map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0x2 << 8; // ISR must do this AFTER setting PCR
|
||||
break;
|
||||
case 6: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
map_MR[pin_6_PWM_channel - 1].PCR_bit = _BV(8 + pin_6_PWM_channel); // enable PWM1 module control of this pin
|
||||
map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM
|
||||
map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0x2 << 10; // ISR must do this AFTER setting PCR
|
||||
break;
|
||||
case 4: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
map_MR[pin_4_PWM_channel - 1].PCR_bit = _BV(8 + pin_4_PWM_channel); // enable PWM1 module control of this pin
|
||||
map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 1; // 0 - available for interrupts, 1 - in use by PWM
|
||||
map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0x2 << 4; // ISR must do this AFTER setting PCR
|
||||
break;
|
||||
default: // ISR pins
|
||||
pinMode(pin, OUTPUT); // set pin to output but don't write anything in case it's already in use
|
||||
break;
|
||||
}
|
||||
|
||||
work_table[slot].microseconds = MAX(MIN(value, work_table[slot].max), work_table[slot].min);
|
||||
work_table[slot].active_flag = true;
|
||||
|
||||
LPC1768_PWM_update();
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool LPC1768_PWM_detach_pin(uint8_t pin) {
|
||||
while (PWM_table_swap) delay(5); // don't do anything until the previous change has been implemented by the ISR
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
uint8_t slot = 0xFF;
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // find slot
|
||||
if (work_table[i].logical_pin == pin) slot = i;
|
||||
if (slot == 0xFF) return false; // return error if pin not found
|
||||
|
||||
LPC1768_PWM_update_map_MR();
|
||||
|
||||
// OK to make these changes before the MR0 interrupt
|
||||
switch(pin) {
|
||||
case 11: // Servo 0, PWM1 channel 2 (Pin 11 P1.20 PWM1.2)
|
||||
LPC_PWM1->PCR &= ~(_BV(8 + pin_11_PWM_channel)); // disable PWM1 module control of this pin
|
||||
map_MR[pin_11_PWM_channel - 1].PCR_bit = 0;
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 8); // return pin to general purpose I/O
|
||||
map_MR[pin_11_PWM_channel - 1].PINSEL3_bits = 0;
|
||||
map_MR[pin_11_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
|
||||
break;
|
||||
case 6: // Servo 1, PWM1 channel 3 (Pin 6 P1.21 PWM1.3)
|
||||
LPC_PWM1->PCR &= ~(_BV(8 + pin_6_PWM_channel)); // disable PWM1 module control of this pin
|
||||
map_MR[pin_6_PWM_channel - 1].PCR_bit = 0;
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 10); // return pin to general purpose I/O
|
||||
map_MR[pin_6_PWM_channel - 1].PINSEL3_bits = 0;
|
||||
map_MR[pin_6_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
|
||||
break;
|
||||
case 4: // Servo 3, PWM1 channel 1 (Pin 4 P1.18 PWM1.1)
|
||||
LPC_PWM1->PCR &= ~(_BV(8 + pin_4_PWM_channel)); // disable PWM1 module control of this pin
|
||||
map_MR[pin_4_PWM_channel - 1].PCR_bit = 0;
|
||||
LPC_PINCON->PINSEL3 &= ~(0x3 << 4); // return pin to general purpose I/O
|
||||
map_MR[pin_4_PWM_channel - 1].PINSEL3_bits = 0;
|
||||
map_MR[pin_4_PWM_channel - 1].map_PWM_INT = 0; // 0 - available for interrupts, 1 - in use by PWM
|
||||
break;
|
||||
}
|
||||
|
||||
pinMode(pin, INPUT);
|
||||
|
||||
work_table[slot] = PWM_MAP_INIT_ROW;
|
||||
|
||||
LPC1768_PWM_update();
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
bool useable_hardware_PWM(uint8_t pin) {
|
||||
COPY_ACTIVE_TABLE; // copy active table into work table
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // see if it's already setup
|
||||
if (work_table[i].logical_pin == pin && work_table[i].sequence) return true;
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) // see if there is an empty slot
|
||||
if (!work_table[i].sequence) return true;
|
||||
return false; // only get here if neither the above are true
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#define HAL_PWM_LPC1768_ISR extern "C" void PWM1_IRQHandler(void)
|
||||
|
||||
|
||||
// Both loops could be terminated when the last active channel is found but that would
|
||||
// result in variations ISR run time which results in variations in pulse width
|
||||
|
||||
/**
|
||||
* Changes to PINSEL3, PCR and MCR are only done during the MR0 interrupt otherwise
|
||||
* the wrong pin may be toggled or even have the system hang.
|
||||
*/
|
||||
|
||||
|
||||
HAL_PWM_LPC1768_ISR {
|
||||
if (PWM_table_swap) ISR_table = work_table; // use old table if a swap was just done
|
||||
else ISR_table = active_table;
|
||||
|
||||
if (LPC_PWM1->IR & 0x1) { // MR0 interrupt
|
||||
ISR_table = active_table; // MR0 means new values could have been loaded so set everything
|
||||
if (PWM_table_swap) LPC_PWM1->MCR = LPC1768_PWM_interrupt_mask; // enable new PWM individual channel interrupts
|
||||
|
||||
for (uint8_t i = 0; i < NUM_PWMS; i++) {
|
||||
if(ISR_table[i].active_flag && !((ISR_table[i].logical_pin == 11) ||
|
||||
(ISR_table[i].logical_pin == 4) ||
|
||||
(ISR_table[i].logical_pin == 6)))
|
||||
*ISR_table[i].set_register = ISR_table[i].write_mask; // set pins for all enabled interrupt channels active
|
||||
if (PWM_table_swap && ISR_table[i].PCR_bit) {
|
||||
LPC_PWM1->PCR |= ISR_table[i].PCR_bit; // enable PWM1 module control of this pin
|
||||
LPC_PINCON->PINSEL3 |= ISR_table[i].PINSEL3_bits; // set pin mode to PWM1 control - must be done after PCR
|
||||
}
|
||||
}
|
||||
PWM_table_swap = false;
|
||||
PWM_MR0_wait = false;
|
||||
LPC_PWM1->IR = 0x01; // clear the MR0 interrupt flag bit
|
||||
}
|
||||
else {
|
||||
for (uint8_t i = 0; i < NUM_PWMS ; i++)
|
||||
if (ISR_table[i].active_flag && (LPC_PWM1->IR & ISR_table[i].PWM_mask) ){
|
||||
LPC_PWM1->IR = ISR_table[i].PWM_mask; // clear the interrupt flag bits for expected interrupts
|
||||
*ISR_table[i].clr_register = ISR_table[i].write_mask; // set channel to inactive
|
||||
}
|
||||
}
|
||||
|
||||
LPC_PWM1->IR = 0x70F; // guarantees all interrupt flags are cleared which, if there is an unexpected
|
||||
// PWM interrupt, will keep the ISR from hanging which will crash the controller
|
||||
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
///////////////// HARDWARE FIRMWARE INTERACTION ////////////////
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
/**
|
||||
* Almost all changes to the hardware registers must be coordinated with the Match Register 0 (MR0)
|
||||
* interrupt. The only exception is detaching pins. It doesn't matter when they go
|
||||
* tristate.
|
||||
*
|
||||
* The LPC1768_PWM_init routine kicks off the MR0 interrupt. This interrupt is never disabled or
|
||||
* delayed.
|
||||
*
|
||||
* The PWM_table_swap flag is set when the firmware has swapped in an updated table. It is
|
||||
* cleared by the ISR during the MR0 interrupt as it completes the swap and accompanying updates.
|
||||
* It serves two purposes:
|
||||
* 1) Tells the ISR that the tables have been swapped
|
||||
* 2) Keeps the firmware from starting a new update until the previous one has been completed.
|
||||
*
|
||||
* The PWM_MR0_wait flag is set when the firmware is ready to swap in an updated table and cleared by
|
||||
* the ISR during the MR0 interrupt. It is used to avoid delaying the MR0 interrupt when swapping in
|
||||
* an updated table. This avoids glitches in pulse width and/or repetition rate.
|
||||
*
|
||||
* The sequence of events during a write to a PWM channel is:
|
||||
* 1) Waits until PWM_table_swap flag is false before starting
|
||||
* 2) Copies the active table into the work table
|
||||
* 3) Updates the work table
|
||||
* NOTES - MR1-MR6 are updated at this time. The updates aren't put into use until the first
|
||||
* MR0 after the LER register has been written. The LER register is written during the
|
||||
* table swap process.
|
||||
* - The MCR mask is created at this time. It is not used until the ISR writes the MCR
|
||||
* during the MR0 interrupt in the table swap process.
|
||||
* 4) Sets the PWM_MR0_wait flag
|
||||
* 5) ISR clears the PWM_MR0_wait flag during the next MR0 interrupt
|
||||
* 6) Once the PWM_MR0_wait flag is cleared then the firmware:
|
||||
* disables the ISR interrupt
|
||||
* swaps the pointers to the tables
|
||||
* writes to the LER register
|
||||
* sets the PWM_table_swap flag active
|
||||
* re-enables the ISR
|
||||
* 7) On the next interrupt the ISR changes its pointer to the work table which is now the old,
|
||||
* unmodified, active table.
|
||||
* 8) On the next MR0 interrupt the ISR:
|
||||
* switches over to the active table
|
||||
* clears the PWM_table_swap and PWM_MR0_wait flags
|
||||
* updates the MCR register with the possibly new interrupt sources/assignments
|
||||
* writes to the PCR register to enable the direct control of the Servo 0, 1 & 3 pins by the PWM1 module
|
||||
* sets the PINSEL3 register to function/mode 0x2 for the Servo 0, 1 & 3 pins
|
||||
* NOTE - PCR must be set before PINSEL
|
||||
* sets the pins controlled by the ISR to their active states
|
||||
*/
|
||||
|
||||
void LPC1768_PWM_init(void);
|
||||
bool LPC1768_PWM_attach_pin(pin_t pin, uint32_t min = 1, uint32_t max = (LPC_PWM1_MR0 - MR0_MARGIN), uint8_t servo_index = 0xff);
|
||||
void LPC1768_PWM_update_map_MR(void);
|
||||
void LPC1768_PWM_update(void);
|
||||
bool LPC1768_PWM_write(pin_t pin, uint32_t value);
|
||||
bool LPC1768_PWM_detach_pin(pin_t pin);
|
||||
bool useable_hardware_PWM(pin_t pin);
|
||||
|
|
|
@ -64,13 +64,10 @@
|
|||
|
||||
#if HAS_SERVOS && defined(TARGET_LPC1768)
|
||||
|
||||
#include "LPC1768_PWM.h"
|
||||
#include "LPC1768_Servo.h"
|
||||
#include "servo_private.h"
|
||||
|
||||
extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
|
||||
extern bool LPC1768_PWM_write(uint8_t, uint32_t);
|
||||
extern bool LPC1768_PWM_detach_pin(uint8_t);
|
||||
|
||||
ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures
|
||||
uint8_t ServoCount = 0; // the total number of attached servos
|
||||
|
||||
|
|
|
@ -40,7 +40,6 @@ http://arduiniana.org.
|
|||
#include <stdarg.h>
|
||||
#include "arduino.h"
|
||||
#include "pinmapping.h"
|
||||
#include "pinmap_re_arm.h"
|
||||
#include "fastio.h"
|
||||
#include "SoftwareSerial.h"
|
||||
|
||||
|
@ -253,8 +252,8 @@ void SoftwareSerial::setRX(uint8_t rx)
|
|||
//if (!_inverse_logic)
|
||||
// digitalWrite(rx, HIGH);
|
||||
_receivePin = rx;
|
||||
_receivePort = pin_map[rx].port;
|
||||
_receivePortPin = pin_map[rx].pin;
|
||||
_receivePort = LPC1768_PIN_PORT(rx);
|
||||
_receivePortPin = LPC1768_PIN_PIN(rx);
|
||||
/* GPIO_T * rxPort = digitalPinToPort(rx);
|
||||
_receivePortRegister = portInputRegister(rxPort);
|
||||
_receiveBitMask = digitalPinToBitMask(rx);*/
|
||||
|
|
|
@ -54,8 +54,8 @@ void attachInterrupt(const uint32_t pin, void (*callback)(void), uint32_t mode)
|
|||
__initialize();
|
||||
++enabled;
|
||||
}
|
||||
uint8_t myport = pin_map[pin].port,
|
||||
mypin = pin_map[pin].pin;
|
||||
uint8_t myport = LPC1768_PIN_PORT(pin),
|
||||
mypin = LPC1768_PIN_PIN(pin);
|
||||
|
||||
if (myport == 0)
|
||||
callbacksP0[mypin] = callback;
|
||||
|
@ -69,8 +69,8 @@ void attachInterrupt(const uint32_t pin, void (*callback)(void), uint32_t mode)
|
|||
void detachInterrupt(const uint32_t pin) {
|
||||
if (!INTERRUPT_PIN(pin)) return;
|
||||
|
||||
const uint8_t myport = pin_map[pin].port,
|
||||
mypin = pin_map[pin].pin;
|
||||
const uint8_t myport = LPC1768_PIN_PORT(pin),
|
||||
mypin = LPC1768_PIN_PIN(pin);
|
||||
|
||||
// Disable interrupt
|
||||
GpioDisableInt(myport, mypin);
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "LPC1768_PWM.h"
|
||||
|
||||
#include <lpc17xx_pinsel.h>
|
||||
|
||||
|
@ -70,26 +71,26 @@ extern "C" void delay(const int msec) {
|
|||
|
||||
// IO functions
|
||||
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
|
||||
void pinMode(uint8_t pin, uint8_t mode) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
void pinMode(pin_t pin, uint8_t mode) {
|
||||
if (!VALID_PIN(pin))
|
||||
return;
|
||||
|
||||
PINSEL_CFG_Type config = { pin_map[pin].port,
|
||||
pin_map[pin].pin,
|
||||
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(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
PINSEL_ConfigPin(&config);
|
||||
break;
|
||||
case OUTPUT:
|
||||
LPC_GPIO(pin_map[pin].port)->FIODIR |= LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
PINSEL_ConfigPin(&config);
|
||||
break;
|
||||
case INPUT_PULLUP:
|
||||
LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
config.Pinmode = PINSEL_PINMODE_PULLUP;
|
||||
PINSEL_ConfigPin(&config);
|
||||
break;
|
||||
|
@ -98,14 +99,14 @@ void pinMode(uint8_t pin, uint8_t mode) {
|
|||
}
|
||||
}
|
||||
|
||||
void digitalWrite(uint8_t pin, uint8_t pin_status) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
void digitalWrite(pin_t pin, uint8_t pin_status) {
|
||||
if (!VALID_PIN(pin))
|
||||
return;
|
||||
|
||||
if (pin_status)
|
||||
LPC_GPIO(pin_map[pin].port)->FIOSET = LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
else
|
||||
LPC_GPIO(pin_map[pin].port)->FIOCLR = LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
|
||||
pinMode(pin, OUTPUT); // Set pin mode on every write (Arduino version does this)
|
||||
|
||||
|
@ -118,23 +119,19 @@ void digitalWrite(uint8_t pin, uint8_t pin_status) {
|
|||
*/
|
||||
}
|
||||
|
||||
bool digitalRead(uint8_t pin) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
|
||||
bool digitalRead(pin_t pin) {
|
||||
if (!VALID_PIN(pin)) {
|
||||
return false;
|
||||
}
|
||||
return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
|
||||
return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
|
||||
}
|
||||
|
||||
void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
|
||||
extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
|
||||
extern bool LPC1768_PWM_write(uint8_t, uint32_t);
|
||||
extern bool LPC1768_PWM_detach_pin(uint8_t);
|
||||
void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
static bool out_of_PWM_slots = false;
|
||||
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
if (!VALID_PIN(pin))
|
||||
return;
|
||||
|
||||
uint value = MAX(MIN(pwm_value, 255), 0);
|
||||
|
@ -155,7 +152,7 @@ void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 2
|
|||
|
||||
extern bool HAL_adc_finished();
|
||||
|
||||
uint16_t analogRead(uint8_t adc_pin) {
|
||||
uint16_t analogRead(pin_t adc_pin) {
|
||||
HAL_adc_start_conversion(adc_pin);
|
||||
while (!HAL_adc_finished()); // Wait for conversion to finish
|
||||
return HAL_adc_get_result();
|
||||
|
|
|
@ -45,15 +45,15 @@ bool useable_hardware_PWM(uint8_t pin);
|
|||
#define LPC_PIN(pin) (1UL << pin)
|
||||
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
|
||||
|
||||
#define SET_DIR_INPUT(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR &= ~LPC_PIN(DIO ## IO ##_PIN))
|
||||
#define SET_DIR_OUTPUT(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIODIR |= LPC_PIN(DIO ## IO ##_PIN))
|
||||
#define SET_DIR_INPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define SET_DIR_OUTPUT(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
|
||||
#define SET_MODE(IO, mode) (pin_mode((DIO ## IO ## _PORT, DIO ## IO ## _PIN), mode))
|
||||
#define SET_MODE(IO, mode) (pin_mode((LPC1768_PIN_PORT(IO), LPC1768_PIN_PIN(IO)), mode))
|
||||
|
||||
#define WRITE_PIN_SET(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIOSET = LPC_PIN(DIO ## IO ##_PIN))
|
||||
#define WRITE_PIN_CLR(IO) (LPC_GPIO(DIO ## IO ## _PORT)->FIOCLR = LPC_PIN(DIO ## IO ##_PIN))
|
||||
#define WRITE_PIN_SET(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
#define WRITE_PIN_CLR(IO) (LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(IO)))
|
||||
|
||||
#define READ_PIN(IO) ((LPC_GPIO(DIO ## IO ## _PORT)->FIOPIN & LPC_PIN(DIO ## IO ##_PIN)) ? 1 : 0)
|
||||
#define READ_PIN(IO) ((LPC_GPIO(LPC1768_PIN_PORT(IO))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(IO))) ? 1 : 0)
|
||||
#define WRITE_PIN(IO, v) ((v) ? WRITE_PIN_SET(IO) : WRITE_PIN_CLR(IO))
|
||||
|
||||
/**
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
// Modified for use with the mcp4451 digipot routine
|
||||
|
||||
#if defined(TARGET_LPC1768)
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#ifndef TwoWire_h
|
||||
#define TwoWire_h
|
||||
|
|
|
@ -26,6 +26,8 @@
|
|||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "../pinmapping.h"
|
||||
|
||||
#define LOW 0x00
|
||||
#define HIGH 0x01
|
||||
#define CHANGE 0x02
|
||||
|
@ -83,6 +85,7 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
|
|||
#define pgm_read_word(addr) pgm_read_word_near(addr)
|
||||
#define pgm_read_dword(addr) pgm_read_dword_near(addr)
|
||||
|
||||
#define memcpy_P memcpy
|
||||
#define sprintf_P sprintf
|
||||
#define strstr_P strstr
|
||||
#define strncpy_P strncpy
|
||||
|
@ -99,11 +102,11 @@ void delayMicroseconds(unsigned long);
|
|||
uint32_t millis();
|
||||
|
||||
//IO functions
|
||||
void pinMode(uint8_t, uint8_t);
|
||||
void digitalWrite(uint8_t, uint8_t);
|
||||
bool digitalRead(uint8_t);
|
||||
void analogWrite(uint8_t, int);
|
||||
uint16_t analogRead(uint8_t);
|
||||
void pinMode(pin_t, uint8_t);
|
||||
void digitalWrite(pin_t, uint8_t);
|
||||
bool digitalRead(pin_t);
|
||||
void analogWrite(pin_t, int);
|
||||
uint16_t analogRead(pin_t);
|
||||
|
||||
// EEPROM
|
||||
void eeprom_write_byte(unsigned char *pos, unsigned char value);
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
|
||||
|
||||
|
||||
#if defined(TARGET_LPC1768)
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
|
|
|
@ -22,8 +22,7 @@ if __name__ == "__main__":
|
|||
|
||||
"-MMD",
|
||||
"-MP",
|
||||
"-DTARGET_LPC1768",
|
||||
"-DIS_REARM"
|
||||
"-DTARGET_LPC1768"
|
||||
])
|
||||
|
||||
for i in range(1, len(sys.argv)):
|
||||
|
|
|
@ -100,7 +100,6 @@ int main(void) {
|
|||
|
||||
HAL_timer_init();
|
||||
|
||||
extern void LPC1768_PWM_init();
|
||||
LPC1768_PWM_init();
|
||||
|
||||
setup();
|
||||
|
|
|
@ -50,7 +50,8 @@ bool access_start() {
|
|||
if (res) MSC_Release_Lock();
|
||||
|
||||
if (res == FR_OK) {
|
||||
uint16_t bytes_written, file_size = f_size(&eeprom_file);
|
||||
UINT bytes_written;
|
||||
FSIZE_t file_size = f_size(&eeprom_file);
|
||||
f_lseek(&eeprom_file, file_size);
|
||||
while (file_size <= E2END && res == FR_OK) {
|
||||
res = f_write(&eeprom_file, &eeprom_erase_value, 1, &bytes_written);
|
||||
|
@ -99,7 +100,7 @@ bool access_finish() {
|
|||
|
||||
bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
|
||||
FRESULT s;
|
||||
uint16_t bytes_written = 0;
|
||||
UINT bytes_written = 0;
|
||||
|
||||
s = f_lseek(&eeprom_file, pos);
|
||||
if (s) {
|
||||
|
@ -128,7 +129,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
|
|||
}
|
||||
|
||||
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
|
||||
uint16_t bytes_read = 0;
|
||||
UINT bytes_read = 0;
|
||||
FRESULT s;
|
||||
s = f_lseek(&eeprom_file, pos);
|
||||
if ( s ) {
|
||||
|
|
|
@ -1,464 +0,0 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __PINMAP_RE_ARM_H__
|
||||
#define __PINMAP_RE_ARM_H__
|
||||
|
||||
// ******************
|
||||
// Runtime pinmapping
|
||||
// ******************
|
||||
|
||||
#if SERIAL_PORT == 0
|
||||
#define NUM_ANALOG_INPUTS 6
|
||||
#else
|
||||
#define NUM_ANALOG_INPUTS 8
|
||||
#endif
|
||||
|
||||
const adc_pin_data adc_pin_map[] = {
|
||||
{0, 23, 0}, //A0 (T0) - D67 - TEMP_0_PIN
|
||||
{0, 24, 1}, //A1 (T1) - D68 - TEMP_BED_PIN
|
||||
{0, 25, 2}, //A2 (T2) - D69 - TEMP_1_PIN
|
||||
{0, 26, 3}, //A3 - D63
|
||||
{1, 30, 4}, //A4 - D37 - BUZZER_PIN
|
||||
{1, 31, 5}, //A5 - D49 - SD_DETECT_PIN
|
||||
#if SERIAL_PORT != 0
|
||||
{0, 3, 6}, //A6 - D0 - RXD0
|
||||
{0, 2, 7} //A7 - D1 - TXD0
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr FORCE_INLINE int8_t analogInputToDigitalPin(int8_t p) {
|
||||
return (p == 0 ? 67:
|
||||
p == 1 ? 68:
|
||||
p == 2 ? 69:
|
||||
p == 3 ? 63:
|
||||
p == 4 ? 37:
|
||||
p == 5 ? 49:
|
||||
#if SERIAL_PORT != 0
|
||||
p == 6 ? 0:
|
||||
p == 7 ? 1:
|
||||
#endif
|
||||
-1);
|
||||
}
|
||||
|
||||
constexpr FORCE_INLINE int8_t DIGITAL_PIN_TO_ANALOG_PIN(int8_t p) {
|
||||
return (p == 67 ? 0:
|
||||
p == 68 ? 1:
|
||||
p == 69 ? 2:
|
||||
p == 63 ? 3:
|
||||
p == 37 ? 4:
|
||||
p == 49 ? 5:
|
||||
#if SERIAL_PORT != 0
|
||||
p == 0 ? 6:
|
||||
p == 1 ? 7:
|
||||
#endif
|
||||
-1);
|
||||
}
|
||||
|
||||
#define NUM_DIGITAL_PINS 84
|
||||
|
||||
#define VALID_PIN(r) (r < 0 ? 0 :\
|
||||
r == 7 ? 0 :\
|
||||
r == 17 ? 0 :\
|
||||
r == 22 ? 0 :\
|
||||
r == 23 ? 0 :\
|
||||
r == 25 ? 0 :\
|
||||
r == 27 ? 0 :\
|
||||
r == 29 ? 0 :\
|
||||
r == 32 ? 0 :\
|
||||
r == 39 ? 0 :\
|
||||
r == 40 ? 0 :\
|
||||
r == 42 ? 0 :\
|
||||
r == 43 ? 0 :\
|
||||
r == 44 ? 0 :\
|
||||
r == 45 ? 0 :\
|
||||
r == 47 ? 0 :\
|
||||
r == 64 ? 0 :\
|
||||
r == 65 ? 0 :\
|
||||
r == 66 ? 0 :\
|
||||
r >= NUM_DIGITAL_PINS ? 0 : 1)
|
||||
|
||||
#define PWM_PIN(r) (r < 0 ? 0 :\
|
||||
r == 3 ? 1 :\
|
||||
r == 4 ? 1 :\
|
||||
r == 6 ? 1 :\
|
||||
r == 9 ? 1 :\
|
||||
r == 10 ? 1 :\
|
||||
r == 11 ? 1 :\
|
||||
r == 14 ? 1 :\
|
||||
r == 26 ? 1 :\
|
||||
r == 46 ? 1 :\
|
||||
r == 53 ? 1 :\
|
||||
r == 54 ? 1 :\
|
||||
r == 60 ? 1 : 0)
|
||||
|
||||
#define NUM_INTERRUPT_PINS 35
|
||||
|
||||
#define INTERRUPT_PIN(r) ( r< 0 ? 0 :\
|
||||
r == 0 ? 1 :\
|
||||
r == 1 ? 1 :\
|
||||
r == 8 ? 1 :\
|
||||
r == 9 ? 1 :\
|
||||
r == 10 ? 1 :\
|
||||
r == 12 ? 1 :\
|
||||
r == 16 ? 1 :\
|
||||
r == 20 ? 1 :\
|
||||
r == 21 ? 1 :\
|
||||
r == 24 ? 1 :\
|
||||
r == 25 ? 1 :\
|
||||
r == 26 ? 1 :\
|
||||
r == 28 ? 1 :\
|
||||
r == 34 ? 1 :\
|
||||
r == 35 ? 1 :\
|
||||
r == 36 ? 1 :\
|
||||
r == 38 ? 1 :\
|
||||
r == 46 ? 1 :\
|
||||
r == 48 ? 1 :\
|
||||
r == 50 ? 1 :\
|
||||
r == 51 ? 1 :\
|
||||
r == 52 ? 1 :\
|
||||
r == 54 ? 1 :\
|
||||
r == 55 ? 1 :\
|
||||
r == 56 ? 1 :\
|
||||
r == 57 ? 1 :\
|
||||
r == 58 ? 1 :\
|
||||
r == 59 ? 1 :\
|
||||
r == 60 ? 1 :\
|
||||
r == 61 ? 1 :\
|
||||
r == 62 ? 1 :\
|
||||
r == 63 ? 1 :\
|
||||
r == 67 ? 1 :\
|
||||
r == 68 ? 1 :\
|
||||
r == 69 ? 1 : 0)
|
||||
/*Internal SD Card */
|
||||
/*r == 80 ? 1 :\
|
||||
r == 81 ? 1 :\
|
||||
r == 82 ? 1 :\
|
||||
r == 83 ? 1 :\*/
|
||||
|
||||
const pin_data pin_map[] = { // pin map for variable pin function
|
||||
{0,3}, // DIO0 RXD0 A6 J4-4 AUX-1
|
||||
{0,2}, // DIO1 TXD0 A7 J4-5 AUX-1
|
||||
{1,25}, // DIO2 X_MAX_PIN 10K PULLUP TO 3.3v, 1K SERIES
|
||||
{1,24}, // DIO3 X_MIN_PIN 10K PULLUP TO 3.3v, 1K SERIES
|
||||
{1,18}, // DIO4 SERVO3_PIN FIL_RUNOUT_PIN 5V output, PWM
|
||||
{1,19}, // DIO5 SERVO2_PIN
|
||||
{1,21}, // DIO6 SERVO1_PIN J5-1
|
||||
{0xFF,0xFF}, // DIO7 N/C
|
||||
{2,7}, // DIO8 RAMPS_D8_PIN
|
||||
{2,4}, // DIO9 RAMPS_D9_PIN PWM
|
||||
{2,5}, // DIO10 RAMPS_D10_PIN PWM
|
||||
{1,20}, // DIO11 SERVO0_PIN
|
||||
{2,12}, // DIO12 PS_ON_PIN
|
||||
{4,28}, // DIO13 LED_PIN
|
||||
{1,26}, // DIO14 Y_MIN_PIN 10K PULLUP TO 3.3v, 1K SERIES
|
||||
{1,27}, // DIO15 Y_MAX_PIN 10K PULLUP TO 3.3v, 1K SERIES
|
||||
{0,16}, // DIO16 LCD_PINS_RS J3-7
|
||||
{0xFF,0xFF}, // DIO17 LCD_PINS_ENABLE MOSI_PIN(MOSI0) J3-10 AUX-3
|
||||
{1,29}, // DIO18 Z_MIN_PIN 10K PULLUP TO 3.3v, 1K SERIES
|
||||
{1,28}, // DIO19 Z_MAX_PIN 10K PULLUP TO 3.3v, 1K SERIES
|
||||
{0,0}, // DIO20 SCA
|
||||
{0,1}, // DIO21 SCL
|
||||
{0xFF,0xFF}, // DIO22 N/C
|
||||
{0xFF,0xFF}, // DIO23 LCD_PINS_D4 SCK_PIN(SCLK0) J3-9 AUX-3
|
||||
{0,4}, // DIO24 E0_ENABLE_PIN
|
||||
{0xFF,0xFF}, // DIO25 N/C
|
||||
{2,0}, // DIO26 E0_STEP_PIN
|
||||
{0xFF,0xFF}, // DIO27 N/C
|
||||
{0,5}, // DIO28 E0_DIR_PIN
|
||||
{0xFF,0xFF}, // DIO29 N/C
|
||||
{4,29}, // DIO30 E1_ENABLE_PIN
|
||||
{3,26}, // DIO31 BTN_EN1
|
||||
{0xFF,0xFF}, // DIO32 N/C
|
||||
{3,25}, // DIO33 BTN_EN2 J3-4
|
||||
{2,13}, // DIO34 E1_DIR_PIN
|
||||
{2,11}, // DIO35 BTN_ENC J3-3
|
||||
{2,8}, // DIO36 E1_STEP_PIN
|
||||
{1,30}, // DIO37 BEEPER_PIN A4 not 5V tolerant
|
||||
{0,10}, // DIO38 X_ENABLE_PIN
|
||||
{0xFF,0xFF}, // DIO39 N/C
|
||||
{0xFF,0xFF}, // DIO40 N/C
|
||||
{1,22}, // DIO41 KILL_PIN J5-4
|
||||
{0xFF,0xFF}, // DIO42 N/C
|
||||
{0xFF,0xFF}, // DIO43 N/C
|
||||
{0xFF,0xFF}, // DIO44 N/C
|
||||
{0xFF,0xFF}, // DIO45 N/C
|
||||
{2,3}, // DIO46 Z_STEP_PIN
|
||||
{0xFF,0xFF}, // DIO47 N/C
|
||||
{0,22}, // DIO48 Z_DIR_PIN
|
||||
{1,31}, // DIO49 SD_DETECT_PIN A5 J3-1 not 5V tolerant
|
||||
{0,17}, // DIO50 MISO_PIN(MISO0) AUX-3
|
||||
{0,18}, // DIO51 MOSI_PIN(MOSI0) LCD_PINS_ENABLE J3-10 AUX-3
|
||||
{0,15}, // DIO52 SCK_PIN(SCLK0) LCD_PINS_D4 J3-9 AUX-3
|
||||
{1,23}, // DIO53 SDSS(SSEL0) J3-5 AUX-3
|
||||
{2,1}, // DIO54 X_STEP_PIN
|
||||
{0,11}, // DIO55 X_DIR_PIN
|
||||
{0,19}, // DIO56 Y_ENABLE_PIN
|
||||
{0,27}, // DIO57 AUX-1 open collector
|
||||
{0,28}, // DIO58 AUX-1 open collector
|
||||
{2,6}, // DIO59 LCD_A0 J3-8 AUX-2
|
||||
{2,2}, // DIO60 Y_STEP_PIN
|
||||
{0,20}, // DIO61 Y_DIR_PIN
|
||||
{0,21}, // DIO62 Z_ENABLE_PIN
|
||||
{0,26}, // DIO63 AUX-2 A3 J5-3 AUX-2
|
||||
{0xFF,0xFF}, // DIO64 N/C
|
||||
{0xFF,0xFF}, // DIO65 N/C
|
||||
{0xFF,0xFF}, // DIO66 N/C
|
||||
{0,23}, // DIO67 TEMP_0_PIN A0
|
||||
{0,24}, // DIO68 TEMP_BED_PIN A1
|
||||
{0,25}, // DIO69 TEMP_1_PIN A2
|
||||
{1,16}, // DIO70 J12-3 ENET_MOC
|
||||
{1,17}, // DIO71 J12-4 ENET_MDIO
|
||||
{1,15}, // DIO72 J12-5 REF_CLK
|
||||
{1,14}, // DIO73 J12-6 ENET_RX_ER
|
||||
{1,9}, // DIO74 J12-7 ENET_RXD0
|
||||
{1,10}, // DIO75 J12-8 ENET_RXD1
|
||||
{1,8}, // DIO76 J12-9 ENET_CRS
|
||||
{1,4}, // DIO77 J12-10 ENET_TX_EN
|
||||
{1,0}, // DIO78 J12-11 ENET_TXD0
|
||||
{1,1}, // DIO79 J12-12 ENET_TXD1
|
||||
{0,14}, // DIO80 MKS-SBASE J7-6 & EXP1-5
|
||||
{0,7}, // DIO81 SD-SCK MKS-SBASE on board SD card and EXP2-2
|
||||
{0,8}, // DIO82 SD-MISO MKS-SBASE on board SD card and EXP2-1
|
||||
{0,9}, // DIO83 SD-MOSI MKS-SBASE n board SD card and EXP2-6
|
||||
// {0,6}, // DIO84 SD-CS on board SD card
|
||||
|
||||
};
|
||||
|
||||
// ***********************
|
||||
// Preprocessor pinmapping
|
||||
// ***********************
|
||||
|
||||
//#define RXD0 0 // A16 J4-4 AUX-1
|
||||
#define DIO0_PORT 0
|
||||
#define DIO0_PIN 3
|
||||
//#define TXD0 1 // A17 J4-5 AUX-1
|
||||
#define DIO1_PORT 0
|
||||
#define DIO1_PIN 2
|
||||
//#define X_MAX_PIN 2 // 10K PULLUP TO 3.3v, 1K SERIES
|
||||
#define DIO2_PORT 1
|
||||
#define DIO2_PIN 25
|
||||
//#define X_MIN_PIN 3 // 10K PULLUP TO 3.3v, 1K SERIES
|
||||
#define DIO3_PORT 1
|
||||
#define DIO3_PIN 24
|
||||
//#define SERVO3_PIN 4 // FIL_RUNOUT_PIN 5V output, PWM
|
||||
#define DIO4_PORT 1
|
||||
#define DIO4_PIN 18
|
||||
//#define SERVO2_PIN 5 //
|
||||
#define DIO5_PORT 1
|
||||
#define DIO5_PIN 19
|
||||
//#define SERVO1_PIN 6 // J5-1
|
||||
#define DIO6_PORT 1
|
||||
#define DIO6_PIN 21
|
||||
//#define RAMPS_D8_PIN 8 //
|
||||
#define DIO8_PORT 2
|
||||
#define DIO8_PIN 7
|
||||
//#define RAMPS_D9_PIN 9 // PWM
|
||||
#define DIO9_PORT 2
|
||||
#define DIO9_PIN 4
|
||||
//#define RAMPS_D10_PIN 10 // PWM
|
||||
#define DIO10_PORT 2
|
||||
#define DIO10_PIN 5
|
||||
//#define SERVO0_PIN 11 //
|
||||
#define DIO11_PORT 1
|
||||
#define DIO11_PIN 20
|
||||
//#define PS_ON_PIN 12 //
|
||||
#define DIO12_PORT 2
|
||||
#define DIO12_PIN 12
|
||||
//#define LED_PIN 13 //
|
||||
#define DIO13_PORT 4
|
||||
#define DIO13_PIN 28
|
||||
//#define Y_MIN_PIN 14 // 10K PULLUP TO 3.3v, 1K SERIES
|
||||
#define DIO14_PORT 1
|
||||
#define DIO14_PIN 26
|
||||
//#define Y_MAX_PIN 15 // 10K PULLUP TO 3.3v, 1K SERIES
|
||||
#define DIO15_PORT 1
|
||||
#define DIO15_PIN 27
|
||||
//#define LCD_PINS_RS 16 // J3-7
|
||||
#define DIO16_PORT 0
|
||||
#define DIO16_PIN 16
|
||||
//#define Z_MIN_PIN 18 // 10K PULLUP TO 3.3v, 1K SERIES
|
||||
#define DIO18_PORT 1
|
||||
#define DIO18_PIN 29
|
||||
//#define Z_MAX_PIN 19 // 10K PULLUP TO 3.3v, 1K SERIES
|
||||
#define DIO19_PORT 1
|
||||
#define DIO19_PIN 28
|
||||
//#define SCA 20 //
|
||||
#define DIO20_PORT 0
|
||||
#define DIO20_PIN 0
|
||||
//#define SCL 21 //
|
||||
#define DIO21_PORT 0
|
||||
#define DIO21_PIN 1
|
||||
//#define E0_ENABLE_PIN 24 //
|
||||
#define DIO24_PORT 0
|
||||
#define DIO24_PIN 4
|
||||
//#define E0_STEP_PIN 26 //
|
||||
#define DIO26_PORT 2
|
||||
#define DIO26_PIN 0
|
||||
//#define E0_DIR_PIN 28 //
|
||||
#define DIO28_PORT 0
|
||||
#define DIO28_PIN 5
|
||||
//#define E1_ENABLE_PIN 30 //
|
||||
#define DIO30_PORT 4
|
||||
#define DIO30_PIN 29
|
||||
//#define BTN_EN1 31 //
|
||||
#define DIO31_PORT 3
|
||||
#define DIO31_PIN 26
|
||||
//#define BTN_EN2 33 // J3-4
|
||||
#define DIO33_PORT 3
|
||||
#define DIO33_PIN 25
|
||||
//#define E1_DIR_PIN 34 //
|
||||
#define DIO34_PORT 2
|
||||
#define DIO34_PIN 13
|
||||
//#define BTN_ENC 35 // J3-3
|
||||
#define DIO35_PORT 2
|
||||
#define DIO35_PIN 11
|
||||
//#define E1_STEP_PIN 36 //
|
||||
#define DIO36_PORT 2
|
||||
#define DIO36_PIN 8
|
||||
//#define BEEPER_PIN 37 // A18 not 5V tolerant
|
||||
#define DIO37_PORT 1
|
||||
#define DIO37_PIN 30
|
||||
//#define X_ENABLE_PIN 38 //
|
||||
#define DIO38_PORT 0
|
||||
#define DIO38_PIN 10
|
||||
//#define KILL_PIN 41 // J5-4
|
||||
#define DIO41_PORT 1
|
||||
#define DIO41_PIN 22
|
||||
//#define Z_STEP_PIN 46 //
|
||||
#define DIO46_PORT 2
|
||||
#define DIO46_PIN 3
|
||||
//#define Z_DIR_PIN 48 //
|
||||
#define DIO48_PORT 0
|
||||
#define DIO48_PIN 22
|
||||
//#define SD_DETECT_PIN 49 // A19 J3-1 not 5V tolerant
|
||||
#define DIO49_PORT 1
|
||||
#define DIO49_PIN 31
|
||||
//#define MISO_PIN(MISO0) 50 // AUX-3
|
||||
#define DIO50_PORT 0
|
||||
#define DIO50_PIN 17
|
||||
//#define MOSI_PIN(MOSI0) 51 // LCD_PINS_ENABLE J3-10 AUX-3
|
||||
#define DIO51_PORT 0
|
||||
#define DIO51_PIN 18
|
||||
//#define SCK_PIN(SCLK0) 52 // LCD_PINS_D4 J3-9 AUX-3
|
||||
#define DIO52_PORT 0
|
||||
#define DIO52_PIN 15
|
||||
//#define SDSS(SSEL0) 53 // J3-5 AUX-3
|
||||
#define DIO53_PORT 1
|
||||
#define DIO53_PIN 23
|
||||
//#define X_STEP_PIN 54 //
|
||||
#define DIO54_PORT 2
|
||||
#define DIO54_PIN 1
|
||||
//#define X_DIR_PIN 55 //
|
||||
#define DIO55_PORT 0
|
||||
#define DIO55_PIN 11
|
||||
//#define Y_ENABLE_PIN 56 //
|
||||
#define DIO56_PORT 0
|
||||
#define DIO56_PIN 19
|
||||
//#define AUX-1 57 // open collector
|
||||
#define DIO57_PORT 0
|
||||
#define DIO57_PIN 27
|
||||
//#define AUX-1 58 // open collector
|
||||
#define DIO58_PORT 0
|
||||
#define DIO58_PIN 28
|
||||
//#define LCD_A0 59 // J3-8 AUX-2
|
||||
#define DIO59_PORT 2
|
||||
#define DIO59_PIN 6
|
||||
//#define Y_STEP_PIN 60 //
|
||||
#define DIO60_PORT 2
|
||||
#define DIO60_PIN 2
|
||||
//#define Y_DIR_PIN 61 //
|
||||
#define DIO61_PORT 0
|
||||
#define DIO61_PIN 20
|
||||
//#define Z_ENABLE_PIN 62 //
|
||||
#define DIO62_PORT 0
|
||||
#define DIO62_PIN 21
|
||||
//#define AUX-2 63 // A9 J5-3 AUX-2
|
||||
#define DIO63_PORT 0
|
||||
#define DIO63_PIN 26
|
||||
//#define TEMP_0_PIN 67 // A13
|
||||
#define DIO67_PORT 0
|
||||
#define DIO67_PIN 23
|
||||
//#define TEMP_BED_PIN 68 // A14
|
||||
#define DIO68_PORT 0
|
||||
#define DIO68_PIN 24
|
||||
//#define TEMP_1_PIN 69 // A15
|
||||
#define DIO69_PORT 0
|
||||
#define DIO69_PIN 25
|
||||
//#define J12-3 70 // ENET_MOC
|
||||
#define DIO70_PORT 1
|
||||
#define DIO70_PIN 16
|
||||
//#define J12-4 71 // ENET_MDIO
|
||||
#define DIO71_PORT 1
|
||||
#define DIO71_PIN 17
|
||||
//#define J12-5 72 // REF_CLK
|
||||
#define DIO72_PORT 1
|
||||
#define DIO72_PIN 15
|
||||
//#define J12-6 73 // ENET_RX_ER
|
||||
#define DIO73_PORT 1
|
||||
#define DIO73_PIN 14
|
||||
//#define J12-7 74 // ENET_RXD0
|
||||
#define DIO74_PORT 1
|
||||
#define DIO74_PIN 9
|
||||
//#define J12-8 75 // ENET_RXD1
|
||||
#define DIO75_PORT 1
|
||||
#define DIO75_PIN 10
|
||||
//#define J12-9 76 // ENET_CRS
|
||||
#define DIO76_PORT 1
|
||||
#define DIO76_PIN 8
|
||||
//#define J12-10 77 // ENET_TX_EN
|
||||
#define DIO77_PORT 1
|
||||
#define DIO77_PIN 4
|
||||
//#define J12-11 78 // ENET_TXD0
|
||||
#define DIO78_PORT 1
|
||||
#define DIO78_PIN 0
|
||||
//#define J12-12 79 // ENET_TXD1
|
||||
#define DIO79_PORT 1
|
||||
#define DIO79_PIN 1
|
||||
//#define J7-6 80 // MKS-SBASE J7-6
|
||||
#define DIO80_PORT 0
|
||||
#define DIO80_PIN 14
|
||||
//#define EXP2-2 81 // MKS-SBASE on board SD card and EXP2
|
||||
#define DIO81_PORT 0
|
||||
#define DIO81_PIN 7
|
||||
//#define EXP2-1 82 // MKS-SBASE on board SD card and EXP2
|
||||
#define DIO82_PORT 0
|
||||
#define DIO82_PIN 8
|
||||
//#define EXP2-6 83 // MKS-SBASE on board SD card and EXP2
|
||||
#define DIO83_PORT 0
|
||||
#define DIO83_PIN 9
|
||||
/**
|
||||
//#define SD-CS 81 // on board SD card
|
||||
#define DIO81_PORT 0
|
||||
#define DIO81_PIN 6
|
||||
//#define SD-SCK 82 // on board SD card
|
||||
#define DIO82_PORT 0
|
||||
#define DIO82_PIN 7
|
||||
//#define SD-MISO 83 // on board SD card
|
||||
#define DIO83_PORT 0
|
||||
#define DIO83_PIN 8
|
||||
//#define SD-MOSI 84 // on board SD card
|
||||
#define DIO84_PORT 0
|
||||
#define DIO84_PIN 9
|
||||
*/
|
||||
|
||||
#endif //__PINMAP_RE_ARM_H__
|
50
Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp
Normal file
50
Marlin/src/HAL/HAL_LPC1768/pinmapping.cpp
Normal file
|
@ -0,0 +1,50 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../../gcode/parser.h"
|
||||
|
||||
int16_t GET_PIN_MAP_INDEX(pin_t pin) {
|
||||
const uint8_t pin_port = LPC1768_PIN_PORT(pin),
|
||||
pin_pin = LPC1768_PIN_PIN(pin);
|
||||
for (size_t i = 0; i < NUM_DIGITAL_PINS; ++i)
|
||||
if (LPC1768_PIN_PORT(pin_map[i]) == pin_port && LPC1768_PIN_PIN(pin_map[i]) == pin_pin)
|
||||
return i;
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
int16_t PARSED_PIN_INDEX(char code, int16_t dval) {
|
||||
if (parser.seenval(code)) {
|
||||
int port, pin;
|
||||
if (sscanf(parser.strval(code), "%d.%d", &port, &pin) == 2)
|
||||
for (size_t i = 0; i < NUM_DIGITAL_PINS; ++i)
|
||||
if (LPC1768_PIN_PORT(pin_map[i]) == port && LPC1768_PIN_PIN(pin_map[i]) == pin)
|
||||
return i;
|
||||
}
|
||||
|
||||
return dval;
|
||||
}
|
||||
|
||||
#endif // TARGET_LPC1768
|
|
@ -24,13 +24,195 @@
|
|||
#define __HAL_PINMAPPING_H__
|
||||
#include "../../core/macros.h"
|
||||
|
||||
struct pin_data { uint8_t port, pin; };
|
||||
struct adc_pin_data { uint8_t port, pin, adc; };
|
||||
typedef int16_t pin_t;
|
||||
|
||||
#if ENABLED(IS_REARM)
|
||||
#include "pinmap_re_arm.h"
|
||||
const uint8_t PIN_FEATURE_INTERRUPT = 1 << 0;
|
||||
const uint8_t PIN_FEATURE_PWM = 1 << 1;
|
||||
constexpr uint8_t PIN_FEATURE_ADC(const int8_t chan) { return (((chan + 1) & 0b1111) << 2); }
|
||||
|
||||
constexpr pin_t LPC1768_PIN(const uint8_t port, const uint8_t pin, const uint8_t feat = 0) {
|
||||
return (((pin_t)feat << 8) | (((pin_t)port & 0x7) << 5) | ((pin_t)pin & 0x1F));
|
||||
}
|
||||
|
||||
constexpr uint8_t LPC1768_PIN_PORT(const pin_t pin) { return ((uint8_t)((pin >> 5) & 0b111)); }
|
||||
constexpr uint8_t LPC1768_PIN_PIN(const pin_t pin) { return ((uint8_t)(pin & 0b11111)); }
|
||||
constexpr bool LPC1768_PIN_INTERRUPT(const pin_t pin) { return (((pin >> 8) & PIN_FEATURE_INTERRUPT) != 0); }
|
||||
constexpr bool LPC1768_PIN_PWM(const pin_t pin) { return (((pin >> 8) & PIN_FEATURE_PWM) != 0); }
|
||||
constexpr int8_t LPC1768_PIN_ADC(const pin_t pin) { return (int8_t)((pin >> 8) & 0b1111) - 1; }
|
||||
|
||||
// ******************
|
||||
// Runtime pinmapping
|
||||
// ******************
|
||||
#if SERIAL_PORT != 3
|
||||
const pin_t P0_0 = LPC1768_PIN(0, 0, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_1 = LPC1768_PIN(0, 1, PIN_FEATURE_INTERRUPT);
|
||||
#endif
|
||||
#if SERIAL_PORT != 0
|
||||
const pin_t P0_2 = LPC1768_PIN(0, 2, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(7));
|
||||
const pin_t P0_3 = LPC1768_PIN(0, 3, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(6));
|
||||
#endif
|
||||
const pin_t P0_4 = LPC1768_PIN(0, 4, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_5 = LPC1768_PIN(0, 5, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_6 = LPC1768_PIN(0, 6, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_7 = LPC1768_PIN(0, 7, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_8 = LPC1768_PIN(0, 8, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_9 = LPC1768_PIN(0, 9, PIN_FEATURE_INTERRUPT);
|
||||
#if SERIAL_PORT != 2
|
||||
const pin_t P0_10 = LPC1768_PIN(0, 10, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_11 = LPC1768_PIN(0, 11, PIN_FEATURE_INTERRUPT);
|
||||
#endif
|
||||
#if SERIAL_PORT != 1
|
||||
const pin_t P0_15 = LPC1768_PIN(0, 15, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_16 = LPC1768_PIN(0, 16, PIN_FEATURE_INTERRUPT);
|
||||
#endif
|
||||
const pin_t P0_17 = LPC1768_PIN(0, 17, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_18 = LPC1768_PIN(0, 18, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_19 = LPC1768_PIN(0, 19, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_20 = LPC1768_PIN(0, 20, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_21 = LPC1768_PIN(0, 21, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_22 = LPC1768_PIN(0, 22, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_23 = LPC1768_PIN(0, 23, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(0));
|
||||
const pin_t P0_24 = LPC1768_PIN(0, 24, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(1));
|
||||
const pin_t P0_25 = LPC1768_PIN(0, 25, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(2));
|
||||
const pin_t P0_26 = LPC1768_PIN(0, 26, PIN_FEATURE_INTERRUPT | PIN_FEATURE_ADC(3));
|
||||
const pin_t P0_27 = LPC1768_PIN(0, 27, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_28 = LPC1768_PIN(0, 28, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_29 = LPC1768_PIN(0, 29, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P0_30 = LPC1768_PIN(0, 30, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P1_0 = LPC1768_PIN(1, 0);
|
||||
const pin_t P1_1 = LPC1768_PIN(1, 1);
|
||||
const pin_t P1_4 = LPC1768_PIN(1, 4);
|
||||
const pin_t P1_8 = LPC1768_PIN(1, 8);
|
||||
const pin_t P1_9 = LPC1768_PIN(1, 9);
|
||||
const pin_t P1_10 = LPC1768_PIN(1, 10);
|
||||
const pin_t P1_14 = LPC1768_PIN(1, 14);
|
||||
const pin_t P1_15 = LPC1768_PIN(1, 15);
|
||||
const pin_t P1_16 = LPC1768_PIN(1, 16);
|
||||
const pin_t P1_17 = LPC1768_PIN(1, 17);
|
||||
const pin_t P1_18 = LPC1768_PIN(1, 18, PIN_FEATURE_PWM);
|
||||
const pin_t P1_19 = LPC1768_PIN(1, 19);
|
||||
const pin_t P1_20 = LPC1768_PIN(1, 20, PIN_FEATURE_PWM);
|
||||
const pin_t P1_21 = LPC1768_PIN(1, 21, PIN_FEATURE_PWM);
|
||||
const pin_t P1_22 = LPC1768_PIN(1, 22);
|
||||
const pin_t P1_23 = LPC1768_PIN(1, 23, PIN_FEATURE_PWM);
|
||||
const pin_t P1_24 = LPC1768_PIN(1, 24, PIN_FEATURE_PWM);
|
||||
const pin_t P1_25 = LPC1768_PIN(1, 25);
|
||||
const pin_t P1_26 = LPC1768_PIN(1, 26, PIN_FEATURE_PWM);
|
||||
const pin_t P1_27 = LPC1768_PIN(1, 27);
|
||||
const pin_t P1_28 = LPC1768_PIN(1, 28);
|
||||
const pin_t P1_29 = LPC1768_PIN(1, 29);
|
||||
const pin_t P1_30 = LPC1768_PIN(1, 30, PIN_FEATURE_ADC(4));
|
||||
const pin_t P1_31 = LPC1768_PIN(1, 31, PIN_FEATURE_ADC(5));
|
||||
const pin_t P2_0 = LPC1768_PIN(2, 0, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
|
||||
const pin_t P2_1 = LPC1768_PIN(2, 1, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
|
||||
const pin_t P2_2 = LPC1768_PIN(2, 2, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
|
||||
const pin_t P2_3 = LPC1768_PIN(2, 3, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
|
||||
const pin_t P2_4 = LPC1768_PIN(2, 4, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
|
||||
const pin_t P2_5 = LPC1768_PIN(2, 5, PIN_FEATURE_INTERRUPT | PIN_FEATURE_PWM);
|
||||
const pin_t P2_6 = LPC1768_PIN(2, 6, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P2_7 = LPC1768_PIN(2, 7, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P2_8 = LPC1768_PIN(2, 8, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P2_9 = LPC1768_PIN(2, 9, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P2_10 = LPC1768_PIN(2, 10, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P2_11 = LPC1768_PIN(2, 11, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P2_12 = LPC1768_PIN(2, 12, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P2_13 = LPC1768_PIN(2, 13, PIN_FEATURE_INTERRUPT);
|
||||
const pin_t P3_25 = LPC1768_PIN(3, 25, PIN_FEATURE_PWM);
|
||||
const pin_t P3_26 = LPC1768_PIN(3, 26, PIN_FEATURE_PWM);
|
||||
const pin_t P4_28 = LPC1768_PIN(4, 28);
|
||||
const pin_t P4_29 = LPC1768_PIN(4, 29);
|
||||
|
||||
constexpr bool VALID_PIN(const pin_t p) {
|
||||
return (
|
||||
#if SERIAL_PORT == 0
|
||||
(LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 1) ||
|
||||
(LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 4, 11)) ||
|
||||
#elif SERIAL_PORT == 2
|
||||
(LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 9) ||
|
||||
#elif SERIAL_PORT == 3
|
||||
(LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 2, 11)) ||
|
||||
#else
|
||||
(LPC1768_PIN_PORT(p) == 0 && LPC1768_PIN_PIN(p) <= 11) ||
|
||||
#endif
|
||||
#if SERIAL_PORT == 1
|
||||
(LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 17, 30)) ||
|
||||
#else
|
||||
(LPC1768_PIN_PORT(p) == 0 && WITHIN(LPC1768_PIN_PIN(p), 15, 30)) ||
|
||||
#endif
|
||||
(LPC1768_PIN_PORT(p) == 1 && LPC1768_PIN_PIN(p) == 1) ||
|
||||
(LPC1768_PIN_PORT(p) == 1 && LPC1768_PIN_PIN(p) == 4) ||
|
||||
(LPC1768_PIN_PORT(p) == 1 && WITHIN(LPC1768_PIN_PIN(p), 8, 10)) ||
|
||||
(LPC1768_PIN_PORT(p) == 1 && WITHIN(LPC1768_PIN_PIN(p), 14, 31)) ||
|
||||
(LPC1768_PIN_PORT(p) == 2 && LPC1768_PIN_PIN(p) <= 13) ||
|
||||
(LPC1768_PIN_PORT(p) == 3 && WITHIN(LPC1768_PIN_PIN(p), 25, 26)) ||
|
||||
(LPC1768_PIN_PORT(p) == 4 && WITHIN(LPC1768_PIN_PIN(p), 28, 29))
|
||||
);
|
||||
}
|
||||
|
||||
constexpr bool PWM_PIN(const pin_t p) {
|
||||
return (VALID_PIN(p) && LPC1768_PIN_PWM(p));
|
||||
}
|
||||
|
||||
constexpr bool INTERRUPT_PIN(const pin_t p) {
|
||||
return (VALID_PIN(p) && LPC1768_PIN_INTERRUPT(p));
|
||||
}
|
||||
|
||||
#if SERIAL_PORT == 0
|
||||
#define NUM_ANALOG_INPUTS 6
|
||||
#else
|
||||
#error "HAL: LPC1768: No defined pin-mapping"
|
||||
#define NUM_ANALOG_INPUTS 8
|
||||
#endif
|
||||
|
||||
constexpr pin_t adc_pin_table[] = {
|
||||
P0_23, P0_24, P0_25, P0_26, P1_30, P1_31,
|
||||
#if SERIAL_PORT != 0
|
||||
P0_3, P0_2
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr pin_t analogInputToDigitalPin(const uint8_t p) {
|
||||
return (p < COUNT(adc_pin_table) ? adc_pin_table[p] : -1);
|
||||
}
|
||||
|
||||
constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
|
||||
return (VALID_PIN(p) ? LPC1768_PIN_ADC(p) : -1);
|
||||
}
|
||||
|
||||
// P0.6 thru P0.9 are for the onboard SD card
|
||||
// P0.29 and P0.30 are for the USB port
|
||||
#define HAL_SENSITIVE_PINS P0_6, P0_7, P0_8, P0_9, P0_29, P0_30
|
||||
|
||||
// Pin map for M43 and M226
|
||||
const pin_t pin_map[] = {
|
||||
#if SERIAL_PORT != 3
|
||||
P0_0, P0_1,
|
||||
#endif
|
||||
#if SERIAL_PORT != 0
|
||||
P0_2, P0_3,
|
||||
#endif
|
||||
P0_4, P0_5, P0_6, P0_7, P0_8, P0_9,
|
||||
#if SERIAL_PORT != 2
|
||||
P0_10, P0_11,
|
||||
#endif
|
||||
#if SERIAL_PORT != 1
|
||||
P0_15, P0_16,
|
||||
#endif
|
||||
P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23, P0_24,
|
||||
P0_25, P0_26, P0_27, P0_28, P0_29, P0_30,
|
||||
P1_0, P1_1, P1_4, P1_8, P1_9, P1_10, P1_14, P1_15,
|
||||
P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23,
|
||||
P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
|
||||
P2_0, P2_1, P2_2, P2_3, P2_4, P2_5, P2_6, P2_7,
|
||||
P2_8, P2_9, P2_10, P2_11, P2_12, P2_13,
|
||||
P3_25, P3_26,
|
||||
P4_28, P4_29
|
||||
};
|
||||
|
||||
#define NUM_DIGITAL_PINS COUNT(pin_map)
|
||||
|
||||
#define GET_PIN_MAP_PIN(i) (WITHIN(i, 0, (int)NUM_DIGITAL_PINS - 1) ? pin_map[i] : -1)
|
||||
|
||||
int16_t GET_PIN_MAP_INDEX(pin_t pin);
|
||||
int16_t PARSED_PIN_INDEX(char code, int16_t dval = 0);
|
||||
|
||||
#endif // __HAL_PINMAPPING_H__
|
||||
|
|
|
@ -21,29 +21,27 @@
|
|||
*/
|
||||
|
||||
/**
|
||||
* Support routines for Re-ARM board
|
||||
* Support routines for LPC1768
|
||||
*/
|
||||
|
||||
bool pin_Re_ARM_output;
|
||||
bool pin_Re_ARM_analog;
|
||||
int8_t pin_Re_ARM_pin;
|
||||
// active ADC function/mode/code values for PINSEL registers
|
||||
int8_t ADC_pin_mode(pin_t pin) {
|
||||
uint8_t pin_port = LPC1768_PIN_PORT(pin);
|
||||
uint8_t pin_port_pin = LPC1768_PIN_PIN(pin);
|
||||
return (pin_port == 0 && pin_port_pin == 2 ? 2 :
|
||||
pin_port == 0 && pin_port_pin == 3 ? 2 :
|
||||
pin_port == 0 && pin_port_pin == 23 ? 1 :
|
||||
pin_port == 0 && pin_port_pin == 24 ? 1 :
|
||||
pin_port == 0 && pin_port_pin == 25 ? 1 :
|
||||
pin_port == 0 && pin_port_pin == 26 ? 1 :
|
||||
pin_port == 1 && pin_port_pin == 30 ? 3 :
|
||||
pin_port == 1 && pin_port_pin == 31 ? 3 : -1);
|
||||
}
|
||||
|
||||
void get_pin_info(int8_t pin) {
|
||||
|
||||
if (pin == 7) return;
|
||||
pin_Re_ARM_analog = 0;
|
||||
pin_Re_ARM_pin = pin;
|
||||
int8_t pin_port = pin_map[pin].port;
|
||||
int8_t pin_port_pin = pin_map[pin].pin;
|
||||
// active ADC function/mode/code values for PINSEL registers
|
||||
int8_t ADC_pin_mode = pin_port == 0 && pin_port_pin == 2 ? 2 :
|
||||
pin_port == 0 && pin_port_pin == 3 ? 2 :
|
||||
pin_port == 0 && pin_port_pin == 23 ? 1 :
|
||||
pin_port == 0 && pin_port_pin == 24 ? 1 :
|
||||
pin_port == 0 && pin_port_pin == 25 ? 1 :
|
||||
pin_port == 0 && pin_port_pin == 26 ? 1 :
|
||||
pin_port == 1 && pin_port_pin == 30 ? 3 :
|
||||
pin_port == 1 && pin_port_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 :
|
||||
|
@ -52,16 +50,22 @@ if (pin == 7) return;
|
|||
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;
|
||||
uint8_t pin_mode = (uint8_t) ((*pinsel_reg >> pinsel_start_bit) & 0x3);
|
||||
uint32_t * FIO_reg[5] PROGMEM = {(uint32_t*) 0x2009C000,(uint32_t*) 0x2009C020,(uint32_t*) 0x2009C040,(uint32_t*) 0x2009C060,(uint32_t*) 0x2009C080};
|
||||
pin_Re_ARM_output = (*FIO_reg[pin_map[pin].port] >> pin_map[pin].pin) & 1; //input/output state except if active ADC
|
||||
int8_t pin_mode = (int8_t) ((*pinsel_reg >> pinsel_start_bit) & 0x3);
|
||||
return pin_mode;
|
||||
}
|
||||
|
||||
if (pin_mode) { // if function/mode/code value not 0 then could be an active analog channel
|
||||
if (ADC_pin_mode == pin_mode) { // found an active analog pin
|
||||
pin_Re_ARM_output = 0;
|
||||
pin_Re_ARM_analog = 1;
|
||||
}
|
||||
}
|
||||
bool GET_PINMODE(pin_t pin) {
|
||||
int8_t pin_mode = get_pin_mode(pin);
|
||||
if (pin_mode == -1 || (pin_mode && pin_mode == ADC_pin_mode(pin))) // found an invalid pin or active analog pin
|
||||
return false;
|
||||
|
||||
uint32_t * FIO_reg[5] PROGMEM = {(uint32_t*) 0x2009C000,(uint32_t*) 0x2009C020,(uint32_t*) 0x2009C040,(uint32_t*) 0x2009C060,(uint32_t*) 0x2009C080};
|
||||
return ((*FIO_reg[LPC1768_PIN_PORT(pin)] >> LPC1768_PIN_PIN(pin) & 1) != 0); //input/output state
|
||||
}
|
||||
|
||||
bool GET_ARRAY_IS_DIGITAL(pin_t pin) {
|
||||
int8_t pin_mode = get_pin_mode(pin);
|
||||
return (pin_mode != -1 && (!get_pin_mode(pin) || pin_mode != ADC_pin_mode(pin)));
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -70,9 +74,7 @@ if (pin == 7) return;
|
|||
|
||||
#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 GET_PIN_INFO(pin) get_pin_info(pin)
|
||||
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
|
||||
#define GET_PINMODE(pin) pin_Re_ARM_output
|
||||
#define digitalRead_mod(p) digitalRead(p)
|
||||
#define digitalPinToPort_DEBUG(p) 0
|
||||
#define digitalPinToBitMask_DEBUG(pin) 0
|
||||
|
@ -81,4 +83,4 @@ if (pin == 7) return;
|
|||
#define NAME_FORMAT(p) PSTR("%-##p##s")
|
||||
// #define PRINT_ARRAY_NAME(x) do {sprintf_P(buffer, NAME_FORMAT(MAX_NAME_LENGTH) , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
|
||||
#define PRINT_ARRAY_NAME(x) do {sprintf_P(buffer, PSTR("%-35s") , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
|
||||
#define GET_ARRAY_IS_DIGITAL(x) !pin_Re_ARM_analog
|
||||
#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%d.%02d "), LPC1768_PIN_PORT(p), LPC1768_PIN_PIN(p)); SERIAL_ECHO(buffer);} while (0)
|
|
@ -31,13 +31,13 @@
|
|||
//#define MOSI_PIN P0_9
|
||||
//#define SS_PIN P0_6
|
||||
/** external */
|
||||
#define SCK_PIN 52 //P0_15
|
||||
#define MISO_PIN 50 //P0_17
|
||||
#define MOSI_PIN 51 //P0_18
|
||||
#define SS_PIN 53 //P1_23
|
||||
#define SCK_PIN P0_15
|
||||
#define MISO_PIN P0_17
|
||||
#define MOSI_PIN P0_18
|
||||
#define SS_PIN P1_23
|
||||
#define SDSS SS_PIN
|
||||
|
||||
#if (defined(IS_REARM) && !(defined(LPC_SOFTWARE_SPI))) // signal LCDs that they need to use the hardware SPI
|
||||
#if (defined(TARGET_LPC1768) && !(defined(LPC_SOFTWARE_SPI))) // signal LCDs that they need to use the hardware SPI
|
||||
#define SHARED_SPI
|
||||
#endif
|
||||
|
||||
|
|
|
@ -98,6 +98,8 @@
|
|||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
typedef int8_t pin_t;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
@ -192,4 +194,8 @@ void HAL_enable_AdcFreerun(void);
|
|||
|
||||
*/
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
||||
#endif // _HAL_STM32F1_H
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
*/
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
#define HAL_TIMER_TYPE uint16_t
|
||||
typedef uint16_t timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFF
|
||||
|
||||
#define STEP_TIMER_NUM 5 // index of timer to use for stepper
|
||||
|
@ -126,8 +126,8 @@ static FORCE_INLINE void HAL_timer_set_count (uint8_t timer_num, uint32_t count)
|
|||
}
|
||||
}
|
||||
|
||||
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
|
||||
HAL_TIMER_TYPE temp;
|
||||
static FORCE_INLINE timer_t HAL_timer_get_count (uint8_t timer_num) {
|
||||
timer_t temp;
|
||||
switch (timer_num) {
|
||||
case STEP_TIMER_NUM:
|
||||
temp = StepperTimer.getCompare(STEP_TIMER_CHAN);
|
||||
|
@ -142,8 +142,8 @@ static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
|
|||
return temp;
|
||||
}
|
||||
|
||||
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(uint8_t timer_num) {
|
||||
HAL_TIMER_TYPE temp;
|
||||
static FORCE_INLINE timer_t HAL_timer_get_current_count(uint8_t timer_num) {
|
||||
timer_t temp;
|
||||
switch (timer_num) {
|
||||
case STEP_TIMER_NUM:
|
||||
temp = StepperTimer.getCount();
|
||||
|
|
|
@ -64,6 +64,8 @@
|
|||
|
||||
#define HAL_SERVO_LIB libServo
|
||||
|
||||
typedef int8_t pin_t;
|
||||
|
||||
#ifndef analogInputToDigitalPin
|
||||
#define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
|
||||
#endif
|
||||
|
@ -139,6 +141,10 @@ uint16_t HAL_adc_get_result(void);
|
|||
//void HAL_disable_AdcFreerun(uint8_t chan);
|
||||
*/
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
//
|
||||
// --------------------------------------------------------------------------
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
#define HAL_TIMER_TYPE uint32_t
|
||||
typedef uint32_t timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
|
||||
|
||||
#define STEP_TIMER_NUM 0
|
||||
|
@ -82,7 +82,7 @@ static FORCE_INLINE void HAL_timer_set_count(const uint8_t timer_num, const uint
|
|||
}
|
||||
}
|
||||
|
||||
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count(const uint8_t timer_num) {
|
||||
static FORCE_INLINE timer_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||
switch(timer_num) {
|
||||
case 0: return FTM0_C0V;
|
||||
case 1: return FTM1_C0V;
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#elif IS_32BIT_TEENSY
|
||||
#include "HAL_TEENSY35_36/HAL_pinsDebug_Teensy.h"
|
||||
#elif defined(TARGET_LPC1768)
|
||||
#include "HAL_LPC1768/pinsDebug_Re_ARM.h"
|
||||
#include "HAL_LPC1768/pinsDebug_LPC1768.h"
|
||||
#else
|
||||
#error Unsupported Platform!
|
||||
#endif
|
||||
|
|
|
@ -297,10 +297,13 @@ void setup_powerhold() {
|
|||
/**
|
||||
* Sensitive pin test for M42, M226
|
||||
*/
|
||||
bool pin_is_protected(const int8_t pin) {
|
||||
static const int8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS;
|
||||
for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
|
||||
if (pin == (int8_t)pgm_read_byte(&sensitive_pins[i])) return true;
|
||||
bool pin_is_protected(const pin_t pin) {
|
||||
static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS;
|
||||
for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) {
|
||||
pin_t sensitive_pin;
|
||||
memcpy_P(&sensitive_pin, &sensitive_pins[i], sizeof(pin_t));
|
||||
if (pin == sensitive_pin) return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -789,7 +792,6 @@ void setup() {
|
|||
#endif
|
||||
|
||||
#if ENABLED(NEOPIXEL_LED)
|
||||
SET_OUTPUT(NEOPIXEL_PIN);
|
||||
setup_neopixel();
|
||||
#endif
|
||||
|
||||
|
|
|
@ -216,7 +216,7 @@ extern millis_t max_inactive_time, stepper_inactive_time;
|
|||
extern int lpq_len;
|
||||
#endif
|
||||
|
||||
bool pin_is_protected(const int8_t pin);
|
||||
bool pin_is_protected(const pin_t pin);
|
||||
|
||||
#if HAS_SUICIDE
|
||||
inline void suicide() { OUT_WRITE(SUICIDE_PIN, LOW); }
|
||||
|
|
|
@ -854,7 +854,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -628,7 +637,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -874,7 +874,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1069,7 +1069,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1638,7 +1638,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -854,7 +854,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -973,7 +973,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1206,7 +1206,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1777,7 +1777,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -860,7 +860,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1055,7 +1055,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1626,7 +1626,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -845,7 +845,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1040,7 +1040,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1609,7 +1609,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -1050,7 +1050,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1619,7 +1619,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -559,11 +559,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -624,7 +633,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -845,7 +845,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1040,7 +1040,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1609,7 +1609,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -853,7 +853,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1048,7 +1048,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1617,7 +1617,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -864,7 +864,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1059,7 +1059,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1628,7 +1628,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
|
|
@ -836,7 +836,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1031,7 +1031,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1600,7 +1600,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -836,7 +836,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1031,7 +1031,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1600,7 +1600,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -851,7 +851,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1046,7 +1046,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1615,7 +1615,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
|
@ -869,7 +869,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1064,7 +1064,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1633,7 +1633,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -854,7 +854,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -858,7 +858,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1053,7 +1053,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1622,7 +1622,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -878,7 +878,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1077,7 +1077,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1646,7 +1646,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -556,14 +556,20 @@
|
|||
// This allows hosts to request long names for files and folders with M33
|
||||
#define LONG_FILENAME_HOST_SUPPORT
|
||||
|
||||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -624,7 +630,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -13,4 +13,3 @@ Configuration files for Micromake C1 with…
|
|||
- 128 STEPS configured with jumper on the motherboard (all open for 128 Steps).
|
||||
- Capacitive Probe (Adjust offsets at your convenience)
|
||||
- French language with no accents for Japanese LCD.
|
||||
|
||||
|
|
|
@ -858,7 +858,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1053,7 +1053,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1622,7 +1622,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -858,7 +858,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1053,7 +1053,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1622,7 +1622,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -563,11 +563,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -628,7 +637,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -856,7 +856,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1051,7 +1051,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1594,7 +1594,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -634,7 +643,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -854,7 +854,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -1047,7 +1047,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -1061,7 +1061,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1630,7 +1630,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -1080,7 +1080,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1649,7 +1649,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -551,11 +551,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -616,7 +625,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -1105,7 +1105,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1674,7 +1674,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -1079,7 +1079,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1653,7 +1653,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -570,11 +570,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -635,7 +644,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -562,11 +562,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -627,7 +636,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -854,7 +854,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1049,7 +1049,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1618,7 +1618,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -496,6 +496,12 @@
|
|||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||
// set the default number of probe points : n*n (1 -> 7)
|
||||
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
||||
|
||||
// Enable and set these values based on results of 'G33 A1'
|
||||
//#define H_FACTOR 1.01
|
||||
//#define R_FACTOR 2.61
|
||||
//#define A_FACTOR 0.87
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
||||
|
@ -978,7 +984,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1176,7 +1182,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1746,7 +1752,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -564,11 +564,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -629,7 +638,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -496,6 +496,12 @@
|
|||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||
// set the default number of probe points : n*n (1 -> 7)
|
||||
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
||||
|
||||
// Enable and set these values based on results of 'G33 A1'
|
||||
//#define H_FACTOR 1.01
|
||||
//#define R_FACTOR 2.61
|
||||
//#define A_FACTOR 0.87
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
||||
|
@ -978,7 +984,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1170,7 +1176,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1739,7 +1745,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -564,11 +564,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -629,7 +638,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -486,6 +486,12 @@
|
|||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||
// set the default number of probe points : n*n (1 -> 7)
|
||||
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
||||
|
||||
// Enable and set these values based on results of 'G33 A1'
|
||||
//#define H_FACTOR 1.01
|
||||
//#define R_FACTOR 2.61
|
||||
//#define A_FACTOR 0.87
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
||||
|
@ -965,7 +971,7 @@
|
|||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||
* A comprehensive bed leveling system combining the features and benefits
|
||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||
* Validation and Mesh Editing systems.
|
||||
* Validation and Mesh Editing systems.
|
||||
*
|
||||
* - MESH_BED_LEVELING
|
||||
* Probe a grid manually
|
||||
|
@ -1165,7 +1171,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1734,7 +1740,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
|
@ -564,11 +564,20 @@
|
|||
// Enable this option to scroll long filenames in the SD card menu
|
||||
//#define SCROLL_LONG_FILENAMES
|
||||
|
||||
// This option allows you to abort SD printing when any endstop is triggered.
|
||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
// To have any effect, endstops must be enabled during SD printing.
|
||||
/**
|
||||
* This option allows you to abort SD printing when any endstop is triggered.
|
||||
* This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||
* To have any effect, endstops must be enabled during SD printing.
|
||||
*/
|
||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||
|
||||
/**
|
||||
* This option makes it easier to print the same SD Card file again.
|
||||
* On print completion the LCD Menu will open with the file selected.
|
||||
* You can just click to start the print, or navigate elsewhere.
|
||||
*/
|
||||
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||
|
||||
#endif // SDSUPPORT
|
||||
|
||||
/**
|
||||
|
@ -629,7 +638,7 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
||||
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||
|
|
|
@ -486,6 +486,12 @@
|
|||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||
// set the default number of probe points : n*n (1 -> 7)
|
||||
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
||||
|
||||
// Enable and set these values based on results of 'G33 A1'
|
||||
//#define H_FACTOR 1.01
|
||||
//#define R_FACTOR 2.61
|
||||
//#define A_FACTOR 0.87
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
||||
|
@ -1168,7 +1174,7 @@
|
|||
//
|
||||
// M100 Free Memory Watcher
|
||||
//
|
||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
||||
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||
|
||||
//
|
||||
// G20/G21 Inch mode support
|
||||
|
@ -1737,7 +1743,7 @@
|
|||
* as the Arduino cannot handle the current the LEDs will require.
|
||||
* Failure to follow this precaution can destroy your Arduino!
|
||||
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* more current than the Arduino 5V linear regulator can produce.
|
||||
* *** CAUTION ***
|
||||
*
|
||||
* LED Type. Enable only one of the following two options.
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Reference in a new issue