Merge pull request #10797 from thinkyhead/bf1_planner_overhaul_ejtagle

[1.1.x] Refactor Stepper / Planner
This commit is contained in:
Scott Lahteine 2018-05-21 13:08:21 -05:00 committed by GitHub
commit f5a4cd76fb
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
18 changed files with 2001 additions and 1411 deletions

305
Marlin/HAL.h Normal file
View File

@ -0,0 +1,305 @@
/* **************************************************************************
Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
****************************************************************************/
/**
* Description: HAL for __AVR__
*/
#ifndef _HAL_AVR_H_
#define _HAL_AVR_H_
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "fastio.h"
#include <stdint.h>
#include <Arduino.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/io.h>
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------
//#define analogInputToDigitalPin(IO) IO
// Bracket code that shouldn't be interrupted
#ifndef CRITICAL_SECTION_START
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
#define CRITICAL_SECTION_END SREG = _sreg;
#endif
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
typedef int8_t pin_t;
#define HAL_SERVO_LIB Servo
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
//extern uint8_t MCUSR;
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
//void cli(void);
//void _delay_ms(const int delay);
inline void HAL_clear_reset_source(void) { MCUSR = 0; }
inline uint8_t HAL_get_reset_source(void) { return MCUSR; }
// eeprom
//void eeprom_write_byte(unsigned char *pos, unsigned char value);
//unsigned char eeprom_read_byte(unsigned char *pos);
// timers
#define HAL_TIMER_RATE ((F_CPU) / 8) // i.e., 2MHz or 2.5MHz
#define STEP_TIMER_NUM 1
#define TEMP_TIMER_NUM 0
#define PULSE_TIMER_NUM TEMP_TIMER_NUM
#define HAL_STEPPER_TIMER_RATE HAL_TIMER_RATE
#define HAL_TICKS_PER_US ((HAL_STEPPER_TIMER_RATE) / 1000000) // Cannot be of type double
#define STEPPER_TIMER_PRESCALE 8
#define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts
#define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0)
#define TIMER_OCR_1 OCR1A
#define TIMER_COUNTER_1 TCNT1
#define TIMER_OCR_0 OCR0A
#define TIMER_COUNTER_0 TCNT0
#define PULSE_TIMER_PRESCALE 8
#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
#define STEPPER_ISR_ENABLED() TEST(TIMSK1, OCIE1A)
#define ENABLE_TEMPERATURE_INTERRUPT() SBI(TIMSK0, OCIE0B)
#define DISABLE_TEMPERATURE_INTERRUPT() CBI(TIMSK0, OCIE0B)
#define TEMPERATURE_ISR_ENABLED() TEST(TIMSK0, OCIE0B)
#define HAL_timer_start(timer_num, frequency)
#define _CAT(a, ...) a ## __VA_ARGS__
#define HAL_timer_set_compare(timer, compare) (_CAT(TIMER_OCR_, timer) = compare)
#define HAL_timer_restrain(timer, interval_ticks) NOLESS(_CAT(TIMER_OCR_, timer), _CAT(TIMER_COUNTER_, timer) + interval_ticks)
#define HAL_timer_get_compare(timer) _CAT(TIMER_OCR_, timer)
#define HAL_timer_get_count(timer) _CAT(TIMER_COUNTER_, timer)
/**
* On AVR there is no hardware prioritization and preemption of
* interrupts, so this emulates it. The UART has first priority
* (otherwise, characters will be lost due to UART overflow).
* Then: Stepper, Endstops, Temperature, and -finally- all others.
*/
#define HAL_timer_isr_prologue(TIMER_NUM)
#define HAL_timer_isr_epilogue(TIMER_NUM)
/* 18 cycles maximum latency */
#define HAL_STEP_TIMER_ISR \
extern "C" void TIMER1_COMPA_vect (void) __attribute__ ((signal, naked, used, externally_visible)); \
extern "C" void TIMER1_COMPA_vect_bottom (void) asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
void TIMER1_COMPA_vect (void) { \
__asm__ __volatile__ ( \
A("push r16") /* 2 Save R16 */ \
A("in r16, __SREG__") /* 1 Get SREG */ \
A("push r16") /* 2 Save SREG into stack */ \
A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \
A("push r16") /* 2 Save TIMSK0 into the stack */ \
A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \
A("sts %[timsk0], r16") /* 2 And set the new value */ \
A("lds r16, %[timsk1]") /* 2 Load into R0 the stepper timer Interrupt mask register [TIMSK1] */ \
A("andi r16,~%[msk1]") /* 1 Disable the stepper ISR */ \
A("sts %[timsk1], r16") /* 2 And set the new value */ \
A("sei") /* 1 Enable global interrupts - stepper and temperature ISRs are disabled, so no risk of reentry or being preempted by the temperature ISR */ \
A("push r16") /* 2 Save TIMSK1 into stack */ \
A("in r16, 0x3B") /* 1 Get RAMPZ register */ \
A("push r16") /* 2 Save RAMPZ into stack */ \
A("in r16, 0x3C") /* 1 Get EIND register */ \
A("push r0") /* C runtime can modify all the following registers without restoring them */ \
A("push r1") \
A("push r18") \
A("push r19") \
A("push r20") \
A("push r21") \
A("push r22") \
A("push r23") \
A("push r24") \
A("push r25") \
A("push r26") \
A("push r27") \
A("push r30") \
A("push r31") \
A("clr r1") /* C runtime expects this register to be 0 */ \
A("call TIMER1_COMPA_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \
A("pop r31") \
A("pop r30") \
A("pop r27") \
A("pop r26") \
A("pop r25") \
A("pop r24") \
A("pop r23") \
A("pop r22") \
A("pop r21") \
A("pop r20") \
A("pop r19") \
A("pop r18") \
A("pop r1") \
A("pop r0") \
A("out 0x3C, r16") /* 1 Restore EIND register */ \
A("pop r16") /* 2 Get the original RAMPZ register value */ \
A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \
A("pop r16") /* 2 Get the original TIMSK1 value but with stepper ISR disabled */ \
A("ori r16,%[msk1]") /* 1 Reenable the stepper ISR */ \
A("cli") /* 1 Disable global interrupts - Reenabling Stepper ISR can reenter amd temperature can reenter, and we want that, if it happens, after this ISR has ended */ \
A("sts %[timsk1], r16") /* 2 And restore the old value - This reenables the stepper ISR */ \
A("pop r16") /* 2 Get the temperature timer Interrupt mask register [TIMSK0] */ \
A("sts %[timsk0], r16") /* 2 And restore the old value - This reenables the temperature ISR */ \
A("pop r16") /* 2 Get the old SREG value */ \
A("out __SREG__, r16") /* 1 And restore the SREG value */ \
A("pop r16") /* 2 Restore R16 value */ \
A("reti") /* 4 Return from interrupt */ \
: \
: [timsk0] "i" ((uint16_t)&TIMSK0), \
[timsk1] "i" ((uint16_t)&TIMSK1), \
[msk0] "M" ((uint8_t)(1<<OCIE0B)),\
[msk1] "M" ((uint8_t)(1<<OCIE1A)) \
: \
); \
} \
void TIMER1_COMPA_vect_bottom(void)
/* 14 cycles maximum latency */
#define HAL_TEMP_TIMER_ISR \
extern "C" void TIMER0_COMPB_vect (void) __attribute__ ((signal, naked, used, externally_visible)); \
extern "C" void TIMER0_COMPB_vect_bottom(void) asm ("TIMER0_COMPB_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
void TIMER0_COMPB_vect (void) { \
__asm__ __volatile__ ( \
A("push r16") /* 2 Save R16 */ \
A("in r16, __SREG__") /* 1 Get SREG */ \
A("push r16") /* 2 Save SREG into stack */ \
A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \
A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \
A("sts %[timsk0], r16") /* 2 And set the new value */ \
A("sei") /* 1 Enable global interrupts - It is safe, as the temperature ISR is disabled, so we cannot reenter it */ \
A("push r16") /* 2 Save TIMSK0 into stack */ \
A("in r16, 0x3B") /* 1 Get RAMPZ register */ \
A("push r16") /* 2 Save RAMPZ into stack */ \
A("in r16, 0x3C") /* 1 Get EIND register */ \
A("push r0") /* C runtime can modify all the following registers without restoring them */ \
A("push r1") \
A("push r18") \
A("push r19") \
A("push r20") \
A("push r21") \
A("push r22") \
A("push r23") \
A("push r24") \
A("push r25") \
A("push r26") \
A("push r27") \
A("push r30") \
A("push r31") \
A("clr r1") /* C runtime expects this register to be 0 */ \
A("call TIMER0_COMPB_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \
A("pop r31") \
A("pop r30") \
A("pop r27") \
A("pop r26") \
A("pop r25") \
A("pop r24") \
A("pop r23") \
A("pop r22") \
A("pop r21") \
A("pop r20") \
A("pop r19") \
A("pop r18") \
A("pop r1") \
A("pop r0") \
A("out 0x3C, r16") /* 1 Restore EIND register */ \
A("pop r16") /* 2 Get the original RAMPZ register value */ \
A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \
A("pop r16") /* 2 Get the original TIMSK0 value but with temperature ISR disabled */ \
A("ori r16,%[msk0]") /* 1 Enable temperature ISR */ \
A("cli") /* 1 Disable global interrupts - We must do this, as we will reenable the temperature ISR, and we don´t want to reenter this handler until the current one is done */ \
A("sts %[timsk0], r16") /* 2 And restore the old value */ \
A("pop r16") /* 2 Get the old SREG */ \
A("out __SREG__, r16") /* 1 And restore the SREG value */ \
A("pop r16") /* 2 Restore R16 */ \
A("reti") /* 4 Return from interrupt */ \
: \
: [timsk0] "i"((uint16_t)&TIMSK0), \
[msk0] "M" ((uint8_t)(1<<OCIE0B)) \
: \
); \
} \
void TIMER0_COMPB_vect_bottom(void)
// ADC
#ifdef DIDR2
#define HAL_ANALOG_SELECT(pin) do{ if (pin < 8) SBI(DIDR0, pin); else SBI(DIDR2, pin & 0x07); }while(0)
#else
#define HAL_ANALOG_SELECT(pin) do{ SBI(DIDR0, pin); }while(0)
#endif
inline void HAL_adc_init(void) {
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
DIDR0 = 0;
#ifdef DIDR2
DIDR2 = 0;
#endif
}
#define SET_ADMUX_ADCSRA(pin) ADMUX = _BV(REFS0) | (pin & 0x07); SBI(ADCSRA, ADSC)
#ifdef MUX5
#define HAL_START_ADC(pin) if (pin > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#else
#define HAL_START_ADC(pin) ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#endif
#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_

View File

@ -23,21 +23,25 @@
#ifndef MARLIN_CONFIG_H
#define MARLIN_CONFIG_H
#include "fastio.h"
#include "macros.h"
#include "boards.h"
#include "macros.h"
#include "Version.h"
#include "Configuration.h"
#include "Conditionals_LCD.h"
#include "Configuration_adv.h"
#include "pins.h"
#if defined(__AVR__) && !defined(USBCON)
#define HardwareSerial_h // trick to disable the standard HWserial
#endif
#include "Arduino.h"
#include "types.h"
#include "HAL.h"
#include "pins.h"
#include "Conditionals_post.h"
#include "SanityCheck.h"
#include <avr/pgmspace.h>
#include "enum.h"
#include "language.h"
#include "utility.h"
#include "serial.h"
#endif // MARLIN_CONFIG_H

View File

@ -336,10 +336,6 @@
#include "I2CPositionEncoder.h"
#endif
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
#include "endstop_interrupts.h"
#endif
#if ENABLED(M100_FREE_MEMORY_WATCHER)
void gcode_M100();
void M100_dump_routine(const char * const title, const char *start, const char *end);
@ -8474,7 +8470,7 @@ inline void gcode_M111() {
*/
inline void gcode_M81() {
thermalManager.disable_all_heaters();
stepper.finish_and_disable();
planner.finish_and_disable();
#if FAN_COUNT > 0
for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0;
@ -8517,7 +8513,7 @@ inline void gcode_M18_M84() {
else {
bool all_axis = !(parser.seen('X') || parser.seen('Y') || parser.seen('Z') || parser.seen('E'));
if (all_axis) {
stepper.finish_and_disable();
planner.finish_and_disable();
}
else {
planner.synchronize();
@ -9963,7 +9959,7 @@ inline void gcode_M400() { planner.synchronize(); }
#endif // FILAMENT_WIDTH_SENSOR
void quickstop_stepper() {
stepper.quick_stop();
planner.quick_stop();
planner.synchronize();
set_current_from_steppers_for_axis(ALL_AXES);
SYNC_PLAN_POSITION_KINEMATIC();
@ -10342,7 +10338,7 @@ inline void gcode_M502() {
* M540: Set whether SD card print should abort on endstop hit (M540 S<0|1>)
*/
inline void gcode_M540() {
if (parser.seen('S')) stepper.abort_on_endstop_hit = parser.value_bool();
if (parser.seen('S')) planner.abort_on_endstop_hit = parser.value_bool();
}
#endif // ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
@ -12995,7 +12991,8 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
idle();
}
LOOP_XYZE(i) raw[i] += segment_distance[i];
planner.buffer_line_kinematic(raw, fr_mm_s, active_extruder, cartesian_segment_mm);
if (!planner.buffer_line_kinematic(raw, fr_mm_s, active_extruder, cartesian_segment_mm))
break;
}
// Since segment_distance is only approximate,
@ -13281,7 +13278,8 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
#if ENABLED(SCARA_FEEDRATE_SCALING)
// For SCARA scale the feed rate from mm/s to degrees/s
// i.e., Complete the angular vector in the given time.
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], raw[Z_AXIS], raw[E_AXIS], HYPOT(delta[A_AXIS] - oldA, delta[B_AXIS] - oldB) * inverse_secs, active_extruder);
if (!planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], raw[Z_AXIS], raw[E_AXIS], HYPOT(delta[A_AXIS] - oldA, delta[B_AXIS] - oldB) * inverse_secs, active_extruder))
break;
/*
SERIAL_ECHO(segments);
SERIAL_ECHOPAIR(": X=", raw[X_AXIS]); SERIAL_ECHOPAIR(" Y=", raw[Y_AXIS]);
@ -13291,7 +13289,8 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
//*/
oldA = delta[A_AXIS]; oldB = delta[B_AXIS];
#else
planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], raw[E_AXIS], _feedrate_mm_s, active_extruder, cartesian_segment_mm);
if (!planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], raw[E_AXIS], _feedrate_mm_s, active_extruder, cartesian_segment_mm))
break;
#endif
}
@ -13385,14 +13384,14 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
}
// unpark extruder: 1) raise, 2) move into starting XY position, 3) lower
for (uint8_t i = 0; i < 3; i++)
planner.buffer_line(
if (!planner.buffer_line(
i == 0 ? raised_parked_position[X_AXIS] : current_position[X_AXIS],
i == 0 ? raised_parked_position[Y_AXIS] : current_position[Y_AXIS],
i == 2 ? current_position[Z_AXIS] : raised_parked_position[Z_AXIS],
current_position[E_AXIS],
i == 1 ? PLANNER_XY_FEEDRATE() : planner.max_feedrate_mm_s[Z_AXIS],
active_extruder
);
active_extruder)
) break;
delayed_move_time = 0;
active_extruder_parked = false;
#if ENABLED(DEBUG_LEVELING_FEATURE)
@ -13409,17 +13408,12 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
}
#endif
// move duplicate extruder into correct duplication position.
planner.set_position_mm(
inactive_extruder_x_pos,
current_position[Y_AXIS],
current_position[Z_AXIS],
current_position[E_AXIS]
);
planner.buffer_line(
planner.set_position_mm(inactive_extruder_x_pos, current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
if (!planner.buffer_line(
current_position[X_AXIS] + duplicate_extruder_x_offset,
current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS],
planner.max_feedrate_mm_s[X_AXIS], 1
);
planner.max_feedrate_mm_s[X_AXIS], 1)
) break;
planner.synchronize();
SYNC_PLAN_POSITION_KINEMATIC();
extruder_duplication_enabled = true;
@ -13652,14 +13646,17 @@ void prepare_move_to_destination() {
// i.e., Complete the angular vector in the given time.
inverse_kinematics(raw);
ADJUST_DELTA(raw);
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], raw[Z_AXIS], raw[E_AXIS], HYPOT(delta[A_AXIS] - oldA, delta[B_AXIS] - oldB) * inverse_secs, active_extruder);
if (!planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], raw[Z_AXIS], raw[E_AXIS], HYPOT(delta[A_AXIS] - oldA, delta[B_AXIS] - oldB) * inverse_secs, active_extruder))
break;
oldA = delta[A_AXIS]; oldB = delta[B_AXIS];
#elif HAS_UBL_AND_CURVES
float pos[XYZ] = { raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS] };
planner.apply_leveling(pos);
planner.buffer_segment(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], raw[E_AXIS], fr_mm_s, active_extruder);
if (!planner.buffer_segment(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], raw[E_AXIS], fr_mm_s, active_extruder))
break;
#else
planner.buffer_line_kinematic(raw, fr_mm_s, active_extruder);
if (!planner.buffer_line_kinematic(raw, fr_mm_s, active_extruder))
break;
#endif
}
@ -14291,7 +14288,9 @@ void setup() {
print_job_timer.init(); // Initial setup of print job timer
stepper.init(); // Initialize stepper, this enables interrupts!
endstops.init(); // Init endstops and pullups
stepper.init(); // Init stepper. This enables interrupts!
servo_init(); // Initialize all servos, stow servo probe
@ -14416,10 +14415,6 @@ void setup() {
i2c.onRequest(i2c_on_request);
#endif
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
setup_endstop_interrupts();
#endif
#if DO_SWITCH_EXTRUDER
move_extruder_servo(0); // Initialize extruder servo
#endif

View File

@ -941,7 +941,7 @@ void CardReader::printingHasFinished() {
#endif
#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
stepper.cleaning_buffer_counter = 1; // The command will fire from the Stepper ISR
planner.finish_and_disable();
#endif
print_job_timer.stop();
if (print_job_timer.duration() > 60)

View File

@ -24,7 +24,7 @@
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the stepper-ISR via endstops.update(), most of the time finding no change.
* the temperature-ISR via endstops.update(), most of the time finding no change.
* With this feature endstops.update() is called only when we know that at
* least one endstop has changed state, saving valuable CPU cycles.
*
@ -40,6 +40,9 @@
#include "macros.h"
// One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.check_possible_change(); }
/**
* Patch for pins_arduino.h (...\Arduino\hardware\arduino\avr\variants\mega\pins_arduino.h)
*
@ -72,8 +75,6 @@
0 )
#endif
volatile uint8_t e_hit = 0; // Different from 0 when the endstops should be tested in detail.
// Must be reset to 0 by the test function when finished.
// Install Pin change interrupt for a pin. Can be called multiple times.
void pciSetup(const int8_t pin) {
@ -82,30 +83,22 @@ void pciSetup(const int8_t pin) {
SBI(PCICR, digitalPinToPCICRbit(pin)); // enable interrupt for the group
}
// This is what is really done inside the interrupts.
FORCE_INLINE void endstop_ISR_worker( void ) {
e_hit = 2; // Because the detection of a e-stop hit has a 1 step debouncer it has to be called at least twice.
}
// Use one Routine to handle each group
// One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstop_ISR_worker(); }
// Handlers for pin change interrupts
#ifdef PCINT0_vect
ISR(PCINT0_vect) { endstop_ISR_worker(); }
ISR(PCINT0_vect) { endstop_ISR(); }
#endif
#ifdef PCINT1_vect
ISR(PCINT1_vect) { endstop_ISR_worker(); }
ISR(PCINT1_vect) { endstop_ISR(); }
#endif
#ifdef PCINT2_vect
ISR(PCINT2_vect) { endstop_ISR_worker(); }
ISR(PCINT2_vect) { endstop_ISR(); }
#endif
#ifdef PCINT3_vect
ISR(PCINT3_vect) { endstop_ISR_worker(); }
ISR(PCINT3_vect) { endstop_ISR(); }
#endif
void setup_endstop_interrupts( void ) {

View File

@ -31,18 +31,27 @@
#include "stepper.h"
#include "ultralcd.h"
// TEST_ENDSTOP: test the old and the current status of an endstop
#define TEST_ENDSTOP(ENDSTOP) (TEST(current_endstop_bits & old_endstop_bits, ENDSTOP))
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
#include "endstop_interrupts.h"
#endif
// TEST_ENDSTOP: test the current status of an endstop
#define TEST_ENDSTOP(ENDSTOP) (TEST(current_endstop_bits, ENDSTOP))
#if HAS_BED_PROBE
#define ENDSTOPS_ENABLED (endstops.enabled || endstops.z_probe_enabled)
#else
#define ENDSTOPS_ENABLED endstops.enabled
#endif
Endstops endstops;
// public:
bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load()
volatile char Endstops::endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
volatile uint8_t Endstops::endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
Endstops::esbits_t Endstops::current_endstop_bits = 0,
Endstops::old_endstop_bits = 0;
Endstops::esbits_t Endstops::current_endstop_bits = 0;
#if HAS_BED_PROBE
volatile bool Endstops::z_probe_enabled = false;
@ -169,8 +178,93 @@ void Endstops::init() {
#endif
#endif
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
setup_endstop_interrupts();
#endif
// Enable endstops
enable_globally(
#if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
true
#else
false
#endif
);
} // Endstops::init
// Called from ISR. A change was detected. Find out what happened!
void Endstops::check_possible_change() { if (ENDSTOPS_ENABLED) endstops.update(); }
// Called from ISR: Poll endstop state if required
void Endstops::poll() {
#if ENABLED(PINS_DEBUGGING)
endstops.run_monitor(); // report changes in endstop status
#endif
#if DISABLED(ENDSTOP_INTERRUPTS_FEATURE)
if (ENDSTOPS_ENABLED) endstops.update();
#endif
}
void Endstops::enable_globally(const bool onoff) {
enabled_globally = enabled = onoff;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
if (onoff) endstops.update(); // If enabling, update state now
#endif
}
// Enable / disable endstop checking
void Endstops::enable(const bool onoff) {
enabled = onoff;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
if (onoff) endstops.update(); // If enabling, update state now
#endif
}
// Disable / Enable endstops based on ENSTOPS_ONLY_FOR_HOMING and global enable
void Endstops::not_homing() {
enabled = enabled_globally;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
if (enabled) endstops.update(); // If enabling, update state now
#endif
}
// Clear endstops (i.e., they were hit intentionally) to suppress the report
void Endstops::hit_on_purpose() {
endstop_hit_bits = 0;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
if (enabled) endstops.update(); // If enabling, update state now
#endif
}
// Enable / disable endstop z-probe checking
#if HAS_BED_PROBE
void Endstops::enable_z_probe(bool onoff) {
z_probe_enabled = onoff;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
if (enabled) endstops.update(); // If enabling, update state now
#endif
}
#endif
#if ENABLED(PINS_DEBUGGING)
void Endstops::run_monitor() {
if (!monitor_flag) return;
static uint8_t monitor_count = 16; // offset this check from the others
monitor_count += _BV(1); // 15 Hz
monitor_count &= 0x7F;
if (!monitor_count) monitor(); // report changes in endstop status
}
#endif
void Endstops::report_state() {
if (endstop_hit_bits) {
#if ENABLED(ULTRA_LCD)
@ -181,7 +275,7 @@ void Endstops::report_state() {
#endif
#define _ENDSTOP_HIT_ECHO(A,C) do{ \
SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", stepper.triggered_position_mm(_AXIS(A))); \
SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); \
_SET_STOP_CHAR(A,C); }while(0)
#define _ENDSTOP_HIT_TEST(A,C) \
@ -211,7 +305,7 @@ void Endstops::report_state() {
hit_on_purpose();
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) && ENABLED(SDSUPPORT)
if (stepper.abort_on_endstop_hit) {
if (planner.abort_on_endstop_hit) {
card.sdprinting = false;
card.closefile();
quickstop_stepper();
@ -273,38 +367,41 @@ void Endstops::M119() {
#endif
} // Endstops::M119
// The following routines are called from an ISR context. It could be the temperature ISR, the
// endstop ISR or the Stepper ISR.
#if ENABLED(X_DUAL_ENDSTOPS)
void Endstops::test_dual_x_endstops(const EndstopEnum es1, const EndstopEnum es2) {
const byte x_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for X, bit 1 for X2
if (x_test && stepper.current_block->steps[X_AXIS] > 0) {
if (x_test && stepper.movement_non_null(X_AXIS)) {
SBI(endstop_hit_bits, X_MIN);
if (!stepper.performing_homing || (x_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
stepper.kill_current_block();
stepper.quick_stop();
}
}
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
void Endstops::test_dual_y_endstops(const EndstopEnum es1, const EndstopEnum es2) {
const byte y_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Y, bit 1 for Y2
if (y_test && stepper.current_block->steps[Y_AXIS] > 0) {
if (y_test && stepper.movement_non_null(Y_AXIS)) {
SBI(endstop_hit_bits, Y_MIN);
if (!stepper.performing_homing || (y_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
stepper.kill_current_block();
stepper.quick_stop();
}
}
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
void Endstops::test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2) {
const byte z_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Z, bit 1 for Z2
if (z_test && stepper.current_block->steps[Z_AXIS] > 0) {
if (z_test && stepper.movement_non_null(Z_AXIS)) {
SBI(endstop_hit_bits, Z_MIN);
if (!stepper.performing_homing || (z_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
stepper.kill_current_block();
stepper.quick_stop();
}
}
#endif
// Check endstops - Called from ISR!
// Check endstops - Could be called from ISR!
void Endstops::update() {
#define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX
@ -322,7 +419,7 @@ void Endstops::update() {
UPDATE_ENDSTOP_BIT(AXIS, MINMAX); \
if (TEST_ENDSTOP(_ENDSTOP(AXIS, MINMAX))) { \
_ENDSTOP_HIT(AXIS, MINMAX); \
stepper.endstop_triggered(_AXIS(AXIS)); \
planner.endstop_triggered(_AXIS(AXIS)); \
} \
}while(0)
@ -331,9 +428,9 @@ void Endstops::update() {
if (G38_move) {
UPDATE_ENDSTOP_BIT(Z, MIN_PROBE);
if (TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE))) {
if (stepper.current_block->steps[_AXIS(X)] > 0) { _ENDSTOP_HIT(X, MIN); stepper.endstop_triggered(_AXIS(X)); }
else if (stepper.current_block->steps[_AXIS(Y)] > 0) { _ENDSTOP_HIT(Y, MIN); stepper.endstop_triggered(_AXIS(Y)); }
else if (stepper.current_block->steps[_AXIS(Z)] > 0) { _ENDSTOP_HIT(Z, MIN); stepper.endstop_triggered(_AXIS(Z)); }
if (stepper.movement_non_null(_AXIS(X))) { _ENDSTOP_HIT(X, MIN); planner.endstop_triggered(_AXIS(X)); }
else if (stepper.movement_non_null(_AXIS(Y))) { _ENDSTOP_HIT(Y, MIN); planner.endstop_triggered(_AXIS(Y)); }
else if (stepper.movement_non_null(_AXIS(Z))) { _ENDSTOP_HIT(Z, MIN); planner.endstop_triggered(_AXIS(Z)); }
G38_endstop_hit = true;
}
}
@ -344,7 +441,7 @@ void Endstops::update() {
*/
#if IS_CORE
#define S_(N) stepper.current_block->steps[CORE_AXIS_##N]
#define S_(N) stepper.movement_non_null(CORE_AXIS_##N)
#define D_(N) stepper.motor_direction(CORE_AXIS_##N)
#endif
@ -364,7 +461,7 @@ void Endstops::update() {
#define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) X_CMP D_(2)) )
#define X_AXIS_HEAD X_HEAD
#else
#define X_MOVE_TEST stepper.current_block->steps[X_AXIS] > 0
#define X_MOVE_TEST stepper.movement_non_null(X_AXIS)
#define X_AXIS_HEAD X_AXIS
#endif
@ -384,7 +481,7 @@ void Endstops::update() {
#define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Y_CMP D_(2)) )
#define Y_AXIS_HEAD Y_HEAD
#else
#define Y_MOVE_TEST stepper.current_block->steps[Y_AXIS] > 0
#define Y_MOVE_TEST stepper.movement_non_null(Y_AXIS)
#define Y_AXIS_HEAD Y_AXIS
#endif
@ -404,13 +501,13 @@ void Endstops::update() {
#define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Z_CMP D_(2)) )
#define Z_AXIS_HEAD Z_HEAD
#else
#define Z_MOVE_TEST stepper.current_block->steps[Z_AXIS] > 0
#define Z_MOVE_TEST stepper.movement_non_null(Z_AXIS)
#define Z_AXIS_HEAD Z_AXIS
#endif
// With Dual X, endstops are only checked in the homing direction for the active extruder
#if ENABLED(DUAL_X_CARRIAGE)
#define E0_ACTIVE stepper.current_block->active_extruder == 0
#define E0_ACTIVE stepper.movement_extruder() == 0
#define X_MIN_TEST ((X_HOME_DIR < 0 && E0_ACTIVE) || (X2_HOME_DIR < 0 && !E0_ACTIVE))
#define X_MAX_TEST ((X_HOME_DIR > 0 && E0_ACTIVE) || (X2_HOME_DIR > 0 && !E0_ACTIVE))
#else
@ -421,124 +518,117 @@ void Endstops::update() {
/**
* Check and update endstops according to conditions
*/
if (stepper.current_block) {
if (X_MOVE_TEST) {
if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction
#if HAS_X_MIN
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MIN);
#if HAS_X2_MIN
UPDATE_ENDSTOP_BIT(X2, MIN);
#else
COPY_BIT(current_endstop_bits, X_MIN, X2_MIN);
#endif
test_dual_x_endstops(X_MIN, X2_MIN);
if (X_MOVE_TEST) {
if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction
#if HAS_X_MIN
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MIN);
#if HAS_X2_MIN
UPDATE_ENDSTOP_BIT(X2, MIN);
#else
if (X_MIN_TEST) UPDATE_ENDSTOP(X, MIN);
COPY_BIT(current_endstop_bits, X_MIN, X2_MIN);
#endif
test_dual_x_endstops(X_MIN, X2_MIN);
#else
if (X_MIN_TEST) UPDATE_ENDSTOP(X, MIN);
#endif
}
else { // +direction
#if HAS_X_MAX
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MAX);
#if HAS_X2_MAX
UPDATE_ENDSTOP_BIT(X2, MAX);
#else
COPY_BIT(current_endstop_bits, X_MAX, X2_MAX);
#endif
test_dual_x_endstops(X_MAX, X2_MAX);
#else
if (X_MAX_TEST) UPDATE_ENDSTOP(X, MAX);
#endif
#endif
}
#endif
}
if (Y_MOVE_TEST) {
if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
#if HAS_Y_MIN
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MIN);
#if HAS_Y2_MIN
UPDATE_ENDSTOP_BIT(Y2, MIN);
#else
COPY_BIT(current_endstop_bits, Y_MIN, Y2_MIN);
#endif
test_dual_y_endstops(Y_MIN, Y2_MIN);
else { // +direction
#if HAS_X_MAX
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MAX);
#if HAS_X2_MAX
UPDATE_ENDSTOP_BIT(X2, MAX);
#else
UPDATE_ENDSTOP(Y, MIN);
COPY_BIT(current_endstop_bits, X_MAX, X2_MAX);
#endif
test_dual_x_endstops(X_MAX, X2_MAX);
#else
if (X_MAX_TEST) UPDATE_ENDSTOP(X, MAX);
#endif
}
else { // +direction
#if HAS_Y_MAX
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MAX);
#if HAS_Y2_MAX
UPDATE_ENDSTOP_BIT(Y2, MAX);
#else
COPY_BIT(current_endstop_bits, Y_MAX, Y2_MAX);
#endif
test_dual_y_endstops(Y_MAX, Y2_MAX);
#else
UPDATE_ENDSTOP(Y, MAX);
#endif
#endif
}
#endif
}
}
if (Z_MOVE_TEST) {
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
#if HAS_Z_MIN
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MIN);
#if HAS_Z2_MIN
UPDATE_ENDSTOP_BIT(Z2, MIN);
#else
COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
#endif
test_dual_z_endstops(Z_MIN, Z2_MIN);
if (Y_MOVE_TEST) {
if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
#if HAS_Y_MIN
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MIN);
#if HAS_Y2_MIN
UPDATE_ENDSTOP_BIT(Y2, MIN);
#else
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
if (z_probe_enabled) UPDATE_ENDSTOP(Z, MIN);
#else
UPDATE_ENDSTOP(Z, MIN);
#endif
COPY_BIT(current_endstop_bits, Y_MIN, Y2_MIN);
#endif
test_dual_y_endstops(Y_MIN, Y2_MIN);
#else
UPDATE_ENDSTOP(Y, MIN);
#endif
// When closing the gap check the enabled probe
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
if (z_probe_enabled) {
UPDATE_ENDSTOP(Z, MIN_PROBE);
if (TEST_ENDSTOP(Z_MIN_PROBE)) SBI(endstop_hit_bits, Z_MIN_PROBE);
}
#endif
}
else { // Z +direction. Gantry up, bed down.
#if HAS_Z_MAX
// Check both Z dual endstops
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MAX);
#if HAS_Z2_MAX
UPDATE_ENDSTOP_BIT(Z2, MAX);
#else
COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
#endif
test_dual_z_endstops(Z_MAX, Z2_MAX);
// If this pin is not hijacked for the bed probe
// then it belongs to the Z endstop
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
UPDATE_ENDSTOP(Z, MAX);
#endif
#endif
}
#endif
}
else { // +direction
#if HAS_Y_MAX
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MAX);
#if HAS_Y2_MAX
UPDATE_ENDSTOP_BIT(Y2, MAX);
#else
COPY_BIT(current_endstop_bits, Y_MAX, Y2_MAX);
#endif
test_dual_y_endstops(Y_MAX, Y2_MAX);
#else
UPDATE_ENDSTOP(Y, MAX);
#endif
#endif
}
}
} // stepper.current_block
old_endstop_bits = current_endstop_bits;
if (Z_MOVE_TEST) {
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
#if HAS_Z_MIN
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MIN);
#if HAS_Z2_MIN
UPDATE_ENDSTOP_BIT(Z2, MIN);
#else
COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
#endif
test_dual_z_endstops(Z_MIN, Z2_MIN);
#else
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
if (z_probe_enabled) UPDATE_ENDSTOP(Z, MIN);
#else
UPDATE_ENDSTOP(Z, MIN);
#endif
#endif
#endif
// When closing the gap check the enabled probe
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
if (z_probe_enabled) {
UPDATE_ENDSTOP(Z, MIN_PROBE);
if (TEST_ENDSTOP(Z_MIN_PROBE)) SBI(endstop_hit_bits, Z_MIN_PROBE);
}
#endif
}
else { // Z +direction. Gantry up, bed down.
#if HAS_Z_MAX
// Check both Z dual endstops
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MAX);
#if HAS_Z2_MAX
UPDATE_ENDSTOP_BIT(Z2, MAX);
#else
COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
#endif
test_dual_z_endstops(Z_MAX, Z2_MAX);
// If this pin is not hijacked for the bed probe
// then it belongs to the Z endstop
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
UPDATE_ENDSTOP(Z, MAX);
#endif
#endif
}
}
} // Endstops::update()

View File

@ -27,15 +27,30 @@
#ifndef __ENDSTOPS_H__
#define __ENDSTOPS_H__
#include "enum.h"
#include "MarlinConfig.h"
enum EndstopEnum : char {
X_MIN,
Y_MIN,
Z_MIN,
Z_MIN_PROBE,
X_MAX,
Y_MAX,
Z_MAX,
X2_MIN,
X2_MAX,
Y2_MIN,
Y2_MAX,
Z2_MIN,
Z2_MAX
};
class Endstops {
public:
static bool enabled, enabled_globally;
static volatile char endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
static volatile uint8_t endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
typedef uint16_t esbits_t;
@ -52,23 +67,26 @@ class Endstops {
typedef byte esbits_t;
#endif
static esbits_t current_endstop_bits, old_endstop_bits;
static esbits_t current_endstop_bits;
Endstops() {
enable_globally(
#if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
true
#else
false
#endif
);
};
Endstops() {};
/**
* Initialize the endstop pins
*/
static void init();
/**
* A change was detected or presumed to be in endstops pins. Find out what
* changed, if anything. Called from ISR contexts
*/
static void check_possible_change();
/**
* Periodic call to poll endstops if required. Called from temperature ISR
*/
static void poll();
/**
* Update the endstops bits from the pins
*/
@ -85,21 +103,28 @@ class Endstops {
static void M119();
// Enable / disable endstop checking globally
static void enable_globally(bool onoff=true) { enabled_globally = enabled = onoff; }
static void enable_globally(const bool onoff=true);
// Enable / disable endstop checking
static void enable(bool onoff=true) { enabled = onoff; }
static void enable(const bool onoff=true);
// Disable / Enable endstops based on ENSTOPS_ONLY_FOR_HOMING and global enable
static void not_homing() { enabled = enabled_globally; }
static void not_homing();
// Clear endstops (i.e., they were hit intentionally) to suppress the report
static void hit_on_purpose() { endstop_hit_bits = 0; }
static void hit_on_purpose();
// Enable / disable endstop z-probe checking
#if HAS_BED_PROBE
static volatile bool z_probe_enabled;
static void enable_z_probe(bool onoff=true) { z_probe_enabled = onoff; }
static void enable_z_probe(bool onoff=true);
#endif
// Debugging of endstops
#if ENABLED(PINS_DEBUGGING)
static bool monitor_flag;
static void monitor();
static void run_monitor();
#endif
private:
@ -117,10 +142,4 @@ class Endstops {
extern Endstops endstops;
#if HAS_BED_PROBE
#define ENDSTOPS_ENABLED (endstops.enabled || endstops.z_probe_enabled)
#else
#define ENDSTOPS_ENABLED endstops.enabled
#endif
#endif // __ENDSTOPS_H__

View File

@ -88,22 +88,6 @@ enum DebugFlags : unsigned char {
DEBUG_ALL = 0xFF
};
enum EndstopEnum : char {
X_MIN,
Y_MIN,
Z_MIN,
Z_MIN_PROBE,
X_MAX,
Y_MAX,
Z_MAX,
X2_MIN,
X2_MAX,
Y2_MIN,
Y2_MAX,
Z2_MIN,
Z2_MAX
};
#if ENABLED(ADVANCED_PAUSE_FEATURE)
enum AdvancedPauseMenuResponse : char {
ADVANCED_PAUSE_RESPONSE_WAIT_FOR,

View File

@ -28,7 +28,6 @@
#include <stdint.h>
typedef int8_t pin_t;
#ifndef _FASTIO_ARDUINO_H_
#define _FASTIO_ARDUINO_H_

View File

@ -47,12 +47,6 @@
#define _O2 __attribute__((optimize("O2")))
#define _O3 __attribute__((optimize("O3")))
// Bracket code that shouldn't be interrupted
#ifndef CRITICAL_SECTION_START
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
#define CRITICAL_SECTION_END SREG = _sreg;
#endif
// Clock speed factors
#define CYCLES_PER_MICROSECOND (F_CPU / 1000000L) // 16 or 20
#define INT0_PRESCALER 8

File diff suppressed because it is too large Load Diff

View File

@ -49,7 +49,7 @@ enum BlockFlagBit : char {
// from a safe speed (in consideration of jerking from zero speed).
BLOCK_BIT_NOMINAL_LENGTH,
// The block is busy
// The block is busy, being interpreted by the stepper ISR
BLOCK_BIT_BUSY,
// The block is segment 2+ of a longer move
@ -80,24 +80,35 @@ typedef struct {
uint8_t flag; // Block flags (See BlockFlag enum above)
unsigned char active_extruder; // The extruder to move (if E move)
// Fields used by the motion planner to manage acceleration
float nominal_speed_sqr, // The nominal speed for this block in (mm/sec)^2
entry_speed_sqr, // Entry speed at previous-current junction in (mm/sec)^2
max_entry_speed_sqr, // Maximum allowable junction entry speed in (mm/sec)^2
millimeters, // The total travel of this block in mm
acceleration; // acceleration mm/sec^2
// Fields used by the Bresenham algorithm for tracing the line
int32_t steps[NUM_AXIS]; // Step count along each axis
union {
// Data used by all move blocks
struct {
// Fields used by the Bresenham algorithm for tracing the line
uint32_t steps[NUM_AXIS]; // Step count along each axis
};
// Data used by all sync blocks
struct {
int32_t position[NUM_AXIS]; // New position to force when this sync block is executed
};
};
uint32_t step_event_count; // The number of step events required to complete this block
uint8_t active_extruder; // The extruder to move (if E move)
#if ENABLED(MIXING_EXTRUDER)
uint32_t mix_event_count[MIXING_STEPPERS]; // Scaled step_event_count for the mixing steppers
#endif
// Settings for the trapezoid generator
int32_t accelerate_until, // The index of the step event on which to stop acceleration
decelerate_after; // The index of the step event on which to start decelerating
uint32_t nominal_rate, // The nominal step rate for this block in step_events/sec
initial_rate, // The jerk-adjusted step rate at start of block
final_rate, // The minimal rate at exit
acceleration_steps_per_s2; // acceleration steps/sec^2
uint32_t accelerate_until, // The index of the step event on which to stop acceleration
decelerate_after; // The index of the step event on which to start decelerating
#if ENABLED(BEZIER_JERK_CONTROL)
uint32_t cruise_rate; // The actual cruise rate to use, between end of the acceleration phase and start of deceleration phase
@ -106,7 +117,7 @@ typedef struct {
uint32_t acceleration_time_inverse, // Inverse of acceleration and deceleration periods, expressed as integer. Scale depends on CPU being used
deceleration_time_inverse;
#else
int32_t acceleration_rate; // The acceleration rate used for acceleration calculation
uint32_t acceleration_rate; // The acceleration rate used for acceleration calculation
#endif
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
@ -120,12 +131,10 @@ typedef struct {
float e_D_ratio;
#endif
// Fields used by the motion planner to manage acceleration
float nominal_speed, // The nominal speed for this block in mm/sec
entry_speed, // Entry speed at previous-current junction in mm/sec
max_entry_speed, // Maximum allowable junction entry speed in mm/sec
millimeters, // The total travel of this block in mm
acceleration; // acceleration mm/sec^2
uint32_t nominal_rate, // The nominal step rate for this block in step_events/sec
initial_rate, // The jerk-adjusted step rate at start of block
final_rate, // The minimal rate at exit
acceleration_steps_per_s2; // acceleration steps/sec^2
#if FAN_COUNT > 0
uint16_t fan_speed[FAN_COUNT];
@ -162,6 +171,10 @@ class Planner {
static block_t block_buffer[BLOCK_BUFFER_SIZE];
static volatile uint8_t block_buffer_head, // Index of the next block to be pushed
block_buffer_tail; // Index of the busy block, if any
static uint16_t cleaning_buffer_counter; // A counter to disable queuing of blocks
static uint8_t delay_before_delivering, // This counter delays delivery of blocks when queue becomes empty to allow the opportunity of merging blocks
block_buffer_planned; // Index of the optimally planned block
#if ENABLED(DISTINCT_E_FACTORS)
static uint8_t last_extruder; // Respond to extruder change
@ -229,6 +242,10 @@ class Planner {
#endif
#endif
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
static bool abort_on_endstop_hit;
#endif
private:
/**
@ -243,9 +260,9 @@ class Planner {
static float previous_speed[NUM_AXIS];
/**
* Nominal speed of previous path line segment
* Nominal speed of previous path line segment (mm/s)^2
*/
static float previous_nominal_speed;
static float previous_nominal_speed_sqr;
/**
* Limit where 64bit math is necessary for acceleration calculation
@ -304,15 +321,6 @@ class Planner {
// Manage fans, paste pressure, etc.
static void check_axes_activity();
/**
* Number of moves currently in the planner
*/
FORCE_INLINE static uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block_buffer_tail + BLOCK_BUFFER_SIZE); }
FORCE_INLINE static void clear_block_buffer() { block_buffer_head = block_buffer_tail = 0; }
FORCE_INLINE static bool is_full() { return block_buffer_tail == next_block_index(block_buffer_head); }
// Update multipliers based on new diameter measurements
static void calculate_volumetric_multipliers();
@ -420,16 +428,32 @@ class Planner {
#define ARG_Z const float &rz
#endif
// Number of moves currently in the planner
FORCE_INLINE static uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block_buffer_tail); }
// Remove all blocks from the buffer
FORCE_INLINE static void clear_block_buffer() { block_buffer_head = block_buffer_tail = 0; }
// Check if movement queue is full
FORCE_INLINE static bool is_full() { return block_buffer_tail == next_block_index(block_buffer_head); }
// Get count of movement slots free
FORCE_INLINE static uint8_t moves_free() { return BLOCK_BUFFER_SIZE - 1 - movesplanned(); }
/**
* Planner::get_next_free_block
*
* - Get the next head index (passed by reference)
* - Wait for a space to open up in the planner
* - Return the head block
* - Get the next head indices (passed by reference)
* - Wait for the number of spaces to open up in the planner
* - Return the first head block
*/
FORCE_INLINE static block_t* get_next_free_block(uint8_t &next_buffer_head) {
FORCE_INLINE static block_t* get_next_free_block(uint8_t &next_buffer_head, const uint8_t count=1) {
// Wait until there are enough slots free
while (moves_free() < count) { idle(); }
// Return the first available block
next_buffer_head = next_block_index(block_buffer_head);
while (block_buffer_tail == next_buffer_head) idle(); // while (is_full)
return &block_buffer[block_buffer_head];
}
@ -442,8 +466,30 @@ class Planner {
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
*
* Returns true if movement was buffered, false otherwise
*/
static void _buffer_steps(const int32_t (&target)[XYZE]
static bool _buffer_steps(const int32_t (&target)[XYZE]
#if HAS_POSITION_FLOAT
, const float (&target_float)[XYZE]
#endif
, float fr_mm_s, const uint8_t extruder, const float &millimeters=0.0
);
/**
* Planner::_populate_block
*
* Fills a new linear movement in the block (in terms of steps).
*
* target - target position in steps units
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
*
* Returns true is movement is acceptable, false otherwise
*/
static bool _populate_block(block_t * const block, bool split_move,
const int32_t (&target)[XYZE]
#if HAS_POSITION_FLOAT
, const float (&target_float)[XYZE]
#endif
@ -468,7 +514,7 @@ class Planner {
* extruder - target extruder
* millimeters - the length of the movement, if known
*/
static void buffer_segment(const float &a, const float &b, const float &c, const float &e, const float &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0);
static bool buffer_segment(const float &a, const float &b, const float &c, const float &e, const float &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0);
static void _set_position_mm(const float &a, const float &b, const float &c, const float &e);
@ -485,11 +531,11 @@ class Planner {
* extruder - target extruder
* millimeters - the length of the movement, if known
*/
FORCE_INLINE static void buffer_line(ARG_X, ARG_Y, ARG_Z, const float &e, const float &fr_mm_s, const uint8_t extruder, const float millimeters = 0.0) {
FORCE_INLINE static bool buffer_line(ARG_X, ARG_Y, ARG_Z, const float &e, const float &fr_mm_s, const uint8_t extruder, const float millimeters = 0.0) {
#if PLANNER_LEVELING && IS_CARTESIAN
apply_leveling(rx, ry, rz);
#endif
buffer_segment(rx, ry, rz, e, fr_mm_s, extruder, millimeters);
return buffer_segment(rx, ry, rz, e, fr_mm_s, extruder, millimeters);
}
/**
@ -502,7 +548,7 @@ class Planner {
* extruder - target extruder
* millimeters - the length of the movement, if known
*/
FORCE_INLINE static void buffer_line_kinematic(const float (&cart)[XYZE], const float &fr_mm_s, const uint8_t extruder, const float millimeters = 0.0) {
FORCE_INLINE static bool buffer_line_kinematic(const float (&cart)[XYZE], const float &fr_mm_s, const uint8_t extruder, const float millimeters = 0.0) {
#if PLANNER_LEVELING
float raw[XYZ] = { cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS] };
apply_leveling(raw);
@ -511,9 +557,9 @@ class Planner {
#endif
#if IS_KINEMATIC
inverse_kinematics(raw);
buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], cart[E_AXIS], fr_mm_s, extruder, millimeters);
return buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], cart[E_AXIS], fr_mm_s, extruder, millimeters);
#else
buffer_segment(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], cart[E_AXIS], fr_mm_s, extruder, millimeters);
return buffer_segment(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], cart[E_AXIS], fr_mm_s, extruder, millimeters);
#endif
}
@ -537,11 +583,6 @@ class Planner {
FORCE_INLINE static void set_z_position_mm(const float &z) { set_position_mm(Z_AXIS, z); }
FORCE_INLINE static void set_e_position_mm(const float &e) { set_position_mm(E_AXIS, e); }
/**
* Sync from the stepper positions. (e.g., after an interrupted move)
*/
static void sync_from_steppers();
/**
* Get an axis position according to stepper position(s)
* For CORE machines apply translation from ABC to XYZ.
@ -553,73 +594,112 @@ class Planner {
FORCE_INLINE static float get_axis_position_degrees(const AxisEnum axis) { return get_axis_position_mm(axis); }
#endif
// Called to force a quick stop of the machine (for example, when an emergency
// stop is required, or when endstops are hit)
static void quick_stop();
// Called when an endstop is triggered. Causes the machine to stop inmediately
static void endstop_triggered(const AxisEnum axis);
// Triggered position of an axis in mm (not core-savvy)
static float triggered_position_mm(const AxisEnum axis);
// Block until all buffered steps are executed / cleaned
static void synchronize();
// Wait for moves to finish and disable all steppers
static void finish_and_disable();
// Periodic tick to handle cleaning timeouts
// Called from the Temperature ISR at ~1kHz
static void tick() {
if (cleaning_buffer_counter) {
--cleaning_buffer_counter;
#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
if (!cleaning_buffer_counter) enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
#endif
}
}
/**
* Does the buffer have any blocks queued?
*/
FORCE_INLINE static bool has_blocks_queued() { return (block_buffer_head != block_buffer_tail); }
//
// Block until all buffered steps are executed
//
static void synchronize();
/**
* "Discard" the block and "release" the memory.
* Called when the current block is no longer needed.
*/
FORCE_INLINE static void discard_current_block() {
if (has_blocks_queued())
block_buffer_tail = BLOCK_MOD(block_buffer_tail + 1);
}
/**
* "Discard" the next block if it's continued.
* Called after an interrupted move to throw away the rest of the move.
*/
FORCE_INLINE static bool discard_continued_block() {
const bool discard = has_blocks_queued() && TEST(block_buffer[block_buffer_tail].flag, BLOCK_BIT_CONTINUED);
if (discard) discard_current_block();
return discard;
}
/**
* The current block. NULL if the buffer is empty.
* This also marks the block as busy.
* WARNING: Called from Stepper ISR context!
*/
static block_t* get_current_block() {
if (has_blocks_queued()) {
// Get the number of moves in the planner queue so far
uint8_t nr_moves = movesplanned();
// If there are any moves queued ...
if (nr_moves) {
// If there is still delay of delivery of blocks running, decrement it
if (delay_before_delivering) {
--delay_before_delivering;
// If the number of movements queued is less than 3, and there is still time
// to wait, do not deliver anything
if (nr_moves < 3 && delay_before_delivering) return NULL;
delay_before_delivering = 0;
}
// If we are here, there is no excuse to deliver the block
block_t * const block = &block_buffer[block_buffer_tail];
// If the block has no trapezoid calculated, it's unsafe to execute.
if (movesplanned() > 1) {
const block_t * const next = &block_buffer[next_block_index(block_buffer_tail)];
if (TEST(block->flag, BLOCK_BIT_RECALCULATE) || TEST(next->flag, BLOCK_BIT_RECALCULATE))
return NULL;
}
else if (TEST(block->flag, BLOCK_BIT_RECALCULATE))
return NULL;
// No trapezoid calculated? Don't execute yet.
if (TEST(block->flag, BLOCK_BIT_RECALCULATE)) return NULL;
#if ENABLED(ULTRA_LCD)
block_buffer_runtime_us -= block->segment_time_us; // We can't be sure how long an active block will take, so don't count it.
#endif
// Mark the block as busy, so the planner does not attempt to replan it
SBI(block->flag, BLOCK_BIT_BUSY);
return block;
}
else {
#if ENABLED(ULTRA_LCD)
clear_block_buffer_runtime(); // paranoia. Buffer is empty now - so reset accumulated time to zero.
#endif
return NULL;
// The queue became empty
#if ENABLED(ULTRA_LCD)
clear_block_buffer_runtime(); // paranoia. Buffer is empty now - so reset accumulated time to zero.
#endif
return NULL;
}
/**
* "Discard" the block and "release" the memory.
* Called when the current block is no longer needed.
* NB: There MUST be a current block to call this function!!
*/
FORCE_INLINE static void discard_current_block() {
if (has_blocks_queued()) { // Discard non-empty buffer.
uint8_t block_index = next_block_index( block_buffer_tail );
// Push block_buffer_planned pointer, if encountered.
if (!has_blocks_queued()) block_buffer_planned = block_index;
block_buffer_tail = block_index;
}
}
#if ENABLED(ULTRA_LCD)
static uint16_t block_buffer_runtime() {
CRITICAL_SECTION_START
millis_t bbru = block_buffer_runtime_us;
CRITICAL_SECTION_END
// Protect the access to the variable. Only required for AVR, as
// any 32bit CPU offers atomic access to 32bit variables
bool was_enabled = STEPPER_ISR_ENABLED();
if (was_enabled) DISABLE_STEPPER_DRIVER_INTERRUPT();
millis_t bbru = block_buffer_runtime_us;
// Reenable Stepper ISR
if (was_enabled) ENABLE_STEPPER_DRIVER_INTERRUPT();
// To translate µs to ms a division by 1000 would be required.
// We introduce 2.4% error here by dividing by 1024.
// Doesn't matter because block_buffer_runtime_us is already too small an estimation.
@ -630,9 +710,15 @@ class Planner {
}
static void clear_block_buffer_runtime() {
CRITICAL_SECTION_START
block_buffer_runtime_us = 0;
CRITICAL_SECTION_END
// Protect the access to the variable. Only required for AVR, as
// any 32bit CPU offers atomic access to 32bit variables
bool was_enabled = STEPPER_ISR_ENABLED();
if (was_enabled) DISABLE_STEPPER_DRIVER_INTERRUPT();
block_buffer_runtime_us = 0;
// Reenable Stepper ISR
if (was_enabled) ENABLE_STEPPER_DRIVER_INTERRUPT();
}
#endif
@ -649,8 +735,8 @@ class Planner {
/**
* Get the index of the next / previous block in the ring buffer
*/
static constexpr int8_t next_block_index(const int8_t block_index) { return BLOCK_MOD(block_index + 1); }
static constexpr int8_t prev_block_index(const int8_t block_index) { return BLOCK_MOD(block_index - 1); }
static constexpr uint8_t next_block_index(const uint8_t block_index) { return BLOCK_MOD(block_index + 1); }
static constexpr uint8_t prev_block_index(const uint8_t block_index) { return BLOCK_MOD(block_index - 1); }
/**
* Calculate the distance (not time) it takes to accelerate
@ -675,12 +761,12 @@ class Planner {
}
/**
* Calculate the maximum allowable speed at this point, in order
* to reach 'target_velocity' using 'acceleration' within a given
* Calculate the maximum allowable speed squared at this point, in order
* to reach 'target_velocity_sqr' using 'acceleration' within a given
* 'distance'.
*/
static float max_allowable_speed(const float &accel, const float &target_velocity, const float &distance) {
return SQRT(sq(target_velocity) - 2 * accel * distance);
static float max_allowable_speed_sqr(const float &accel, const float &target_velocity_sqr, const float &distance) {
return target_velocity_sqr - 2 * accel * distance;
}
#if ENABLED(BEZIER_JERK_CONTROL)
@ -695,7 +781,7 @@ class Planner {
static void calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor);
static void reverse_pass_kernel(block_t* const current, const block_t * const next);
static void forward_pass_kernel(const block_t * const previous, block_t* const current);
static void forward_pass_kernel(const block_t * const previous, block_t* const current, uint8_t block_index);
static void reverse_pass();
static void forward_pass();

View File

@ -41,8 +41,7 @@
#define MAX_STEP 0.1
#define SIGMA 0.1
/* Compute the linear interpolation between to real numbers.
*/
// Compute the linear interpolation between two real numbers.
inline static float interp(float a, float b, float t) { return (1.0 - t) * a + t * b; }
/**
@ -188,12 +187,15 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
bez_target[Z_AXIS] = interp(position[Z_AXIS], target[Z_AXIS], t);
bez_target[E_AXIS] = interp(position[E_AXIS], target[E_AXIS], t);
clamp_to_software_endstops(bez_target);
#if HAS_UBL_AND_CURVES
float pos[XYZ] = { bez_target[X_AXIS], bez_target[Y_AXIS], bez_target[Z_AXIS] };
planner.apply_leveling(pos);
planner.buffer_segment(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], bez_target[E_AXIS], fr_mm_s, active_extruder);
if (!planner.buffer_segment(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], bez_target[E_AXIS], fr_mm_s, active_extruder))
break;
#else
planner.buffer_line_kinematic(bez_target, fr_mm_s, extruder);
if (!planner.buffer_line_kinematic(bez_target, fr_mm_s, extruder))
break;
#endif
}
}

File diff suppressed because it is too large Load Diff

View File

@ -52,11 +52,6 @@
class Stepper;
extern Stepper stepper;
#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
#define STEPPER_ISR_ENABLED() TEST(TIMSK1, OCIE1A)
#define HAL_STEPPER_TIMER_RATE ((F_CPU) * 0.125)
// intRes = intIn1 * intIn2 >> 16
// uses:
// r26 to store 0
@ -90,10 +85,6 @@ class Stepper {
static block_t* current_block; // A pointer to the block currently being traced
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
static bool abort_on_endstop_hit;
#endif
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
static bool performing_homing;
#endif
@ -105,11 +96,12 @@ class Stepper {
static uint32_t motor_current_setting[3];
#endif
static int16_t cleaning_buffer_counter;
private:
static uint8_t last_direction_bits; // The next stepping-bits to be output
static uint8_t last_direction_bits, // The next stepping-bits to be output
last_movement_extruder; // Last movement extruder, as computed when the last movement was fetched from planner
static bool abort_current_block, // Signals to the stepper that current block should be aborted
last_movement_non_null[NUM_AXIS]; // Last Movement in the given direction is not null, as computed when the last movement was fetched from planner
#if ENABLED(X_DUAL_ENDSTOPS)
static bool locked_x_motor, locked_x2_motor;
@ -123,7 +115,7 @@ class Stepper {
// Counter variables for the Bresenham line tracer
static int32_t counter_X, counter_Y, counter_Z, counter_E;
static volatile uint32_t step_events_completed; // The number of step events executed in the current block
static uint32_t step_events_completed; // The number of step events executed in the current block
#if ENABLED(BEZIER_JERK_CONTROL)
static int32_t bezier_A, // A coefficient in Bézier speed curve
@ -135,12 +127,14 @@ class Stepper {
bezier_2nd_half; // If Bézier curve has been initialized or not
#endif
static uint32_t nextMainISR; // time remaining for the next Step ISR
static bool all_steps_done; // all steps done
#if ENABLED(LIN_ADVANCE)
static uint32_t LA_decelerate_after; // Copy from current executed block. Needed because current_block is set to NULL "too early".
static uint16_t nextMainISR, nextAdvanceISR, eISR_Rate, current_adv_steps,
final_adv_steps, max_adv_steps; // Copy from current executed block. Needed because current_block is set to NULL "too early".
#define _NEXT_ISR(T) nextMainISR = T
static uint32_t nextAdvanceISR, eISR_Rate;
static uint16_t current_adv_steps, final_adv_steps, max_adv_steps; // Copy from current executed block. Needed because current_block is set to NULL "too early".
static int8_t e_steps;
static bool use_advance_lead;
#if E_STEPPERS > 1
@ -149,18 +143,14 @@ class Stepper {
static constexpr int8_t LA_active_extruder = 0;
#endif
#else // !LIN_ADVANCE
#endif // LIN_ADVANCE
#define _NEXT_ISR(T) OCR1A = T
#endif // !LIN_ADVANCE
static int32_t acceleration_time, deceleration_time;
static uint32_t acceleration_time, deceleration_time;
static uint8_t step_loops, step_loops_nominal;
static uint16_t OCR1A_nominal;
static uint32_t ticks_nominal;
#if DISABLED(BEZIER_JERK_CONTROL)
static uint16_t acc_step_rate; // needed for deceleration start point
static uint32_t acc_step_rate; // needed for deceleration start point
#endif
static volatile int32_t endstops_trigsteps[XYZ];
@ -193,88 +183,53 @@ class Stepper {
//
Stepper() { };
//
// Initialize stepper hardware
//
static void init();
//
// Interrupt Service Routines
//
static void isr();
// The ISR scheduler
static hal_timer_t isr_scheduler();
// The stepper pulse phase ISR
static void stepper_pulse_phase_isr();
// The stepper block processing phase ISR
static uint32_t stepper_block_phase_isr();
#if ENABLED(LIN_ADVANCE)
static void advance_isr();
static void advance_isr_scheduler();
// The Linear advance stepper ISR
static uint32_t advance_isr();
#endif
//
// Set the current position in steps
//
static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e);
FORCE_INLINE static void _set_position(const AxisEnum a, const int32_t &v) { count_position[a] = v; }
FORCE_INLINE static void set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) {
planner.synchronize();
CRITICAL_SECTION_START;
_set_position(a, b, c, e);
CRITICAL_SECTION_END;
}
static void set_position(const AxisEnum a, const int32_t &v) {
planner.synchronize();
CRITICAL_SECTION_START;
count_position[a] = v;
CRITICAL_SECTION_END;
}
FORCE_INLINE static void _set_e_position(const int32_t &e) { count_position[E_AXIS] = e; }
static void set_e_position(const int32_t &e) {
planner.synchronize();
CRITICAL_SECTION_START;
count_position[E_AXIS] = e;
CRITICAL_SECTION_END;
}
//
// Set direction bits for all steppers
//
static void set_directions();
//
// Get the position of a stepper, in steps
//
static int32_t position(const AxisEnum axis);
//
// Report the positions of the steppers, in steps
//
static void report_positions();
//
// The stepper subsystem goes to sleep when it runs out of things to execute. Call this
// to notify the subsystem that it is time to go to work.
//
static void wake_up();
//
// Wait for moves to finish and disable all steppers
//
static void finish_and_disable();
// Quickly stop all steppers
FORCE_INLINE static void quick_stop() { abort_current_block = true; }
//
// Quickly stop all steppers and clear the blocks queue
//
static void quick_stop();
//
// The direction of a single motor
//
FORCE_INLINE static bool motor_direction(const AxisEnum axis) { return TEST(last_direction_bits, axis); }
// The last movement direction was not null on the specified axis. Note that motor direction is not necessarily the same.
FORCE_INLINE static bool movement_non_null(const AxisEnum axis) { return last_movement_non_null[axis]; }
// The extruder associated to the last movement
FORCE_INLINE static uint8_t movement_extruder() { return last_movement_extruder; }
// Handle a triggered endstop
static void endstop_triggered(const AxisEnum axis);
// Triggered position of an axis in steps
static int32_t triggered_position(const AxisEnum axis);
#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
static void digitalPotWrite(const int16_t address, const int16_t value);
static void digipot_current(const uint8_t driver, const int16_t current);
@ -306,32 +261,22 @@ class Stepper {
static void babystep(const AxisEnum axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif
static inline void kill_current_block() {
step_events_completed = current_block->step_event_count;
}
//
// Handle a triggered endstop
//
static void endstop_triggered(const AxisEnum axis);
//
// Triggered position of an axis in mm (not core-savvy)
//
FORCE_INLINE static float triggered_position_mm(const AxisEnum axis) {
return endstops_trigsteps[axis] * planner.steps_to_mm[axis];
}
#if HAS_MOTOR_CURRENT_PWM
static void refresh_motor_power();
#endif
private:
FORCE_INLINE static uint16_t calc_timer_interval(uint16_t step_rate) {
uint16_t timer;
// Set the current position in steps
static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e);
NOMORE(step_rate, MAX_STEP_FREQUENCY);
// Set direction bits for all steppers
static void set_directions();
FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate) {
uint32_t timer;
NOMORE(step_rate, uint32_t(MAX_STEP_FREQUENCY));
if (step_rate > 20000) { // If steprate > 20kHz >> step 4 times
step_rate >>= 2;
@ -345,12 +290,14 @@ class Stepper {
step_loops = 1;
}
NOLESS(step_rate, F_CPU / 500000);
NOLESS(step_rate, uint32_t(F_CPU / 500000U));
step_rate -= F_CPU / 500000; // Correct for minimal speed
if (step_rate >= (8 * 256)) { // higher step rate
uint16_t table_address = (uint16_t)&speed_lookuptable_fast[(uint8_t)(step_rate >> 8)][0],
gain = (uint16_t)pgm_read_word_near(table_address + 2);
timer = (uint16_t)pgm_read_word_near(table_address) - MultiU16X8toH16(step_rate & 0x00FF, gain);
const uint8_t tmp_step_rate = (step_rate & 0x00FF);
const uint16_t table_address = (uint16_t)&speed_lookuptable_fast[(uint8_t)(step_rate >> 8)][0],
gain = (uint16_t)pgm_read_word_near(table_address + 2);
timer = MultiU16X8toH16(tmp_step_rate, gain);
timer = (uint16_t)pgm_read_word_near(table_address) - timer;
}
else { // lower step rates
uint16_t table_address = (uint16_t)&speed_lookuptable_slow[0][0];
@ -360,9 +307,9 @@ class Stepper {
}
if (timer < 100) { // (20kHz - this should never happen)
timer = 100;
SERIAL_PROTOCOL(MSG_STEPPER_TOO_HIGH);
SERIAL_PROTOCOLLN(step_rate);
SERIAL_ECHOLNPAIR(MSG_STEPPER_TOO_HIGH, step_rate);
}
return timer;
}

View File

@ -32,6 +32,7 @@
#include "language.h"
#include "printcounter.h"
#include "delay.h"
#include "endstops.h"
#if ENABLED(HEATER_0_USES_MAX6675)
#include "MarlinSPI.h"
@ -41,10 +42,6 @@
#include "stepper.h"
#endif
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
#include "endstops.h"
#endif
#if ENABLED(USE_WATCHDOG)
#include "watchdog.h"
#endif
@ -1066,9 +1063,7 @@ void Temperature::updateTemperaturesFromRawValues() {
watchdog_reset();
#endif
CRITICAL_SECTION_START;
temp_meas_ready = false;
CRITICAL_SECTION_END;
}
@ -1179,43 +1174,38 @@ void Temperature::init() {
#endif // HEATER_0_USES_MAX6675
#ifdef DIDR2
#define ANALOG_SELECT(pin) do{ if (pin < 8) SBI(DIDR0, pin); else SBI(DIDR2, pin & 0x07); }while(0)
#else
#define ANALOG_SELECT(pin) do{ SBI(DIDR0, pin); }while(0)
#endif
HAL_adc_init();
// Set analog inputs
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
DIDR0 = 0;
#ifdef DIDR2
DIDR2 = 0;
#endif
#if HAS_TEMP_ADC_0
ANALOG_SELECT(TEMP_0_PIN);
HAL_ANALOG_SELECT(TEMP_0_PIN);
#endif
#if HAS_TEMP_ADC_1
ANALOG_SELECT(TEMP_1_PIN);
HAL_ANALOG_SELECT(TEMP_1_PIN);
#endif
#if HAS_TEMP_ADC_2
ANALOG_SELECT(TEMP_2_PIN);
HAL_ANALOG_SELECT(TEMP_2_PIN);
#endif
#if HAS_TEMP_ADC_3
ANALOG_SELECT(TEMP_3_PIN);
HAL_ANALOG_SELECT(TEMP_3_PIN);
#endif
#if HAS_TEMP_ADC_4
ANALOG_SELECT(TEMP_4_PIN);
HAL_ANALOG_SELECT(TEMP_4_PIN);
#endif
#if HAS_HEATED_BED
ANALOG_SELECT(TEMP_BED_PIN);
HAL_ANALOG_SELECT(TEMP_BED_PIN);
#endif
#if HAS_TEMP_CHAMBER
ANALOG_SELECT(TEMP_CHAMBER_PIN);
HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN);
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
ANALOG_SELECT(FILWIDTH_PIN);
HAL_ANALOG_SELECT(FILWIDTH_PIN);
#endif
// Use timer0 for temperature measurement
// Interleave temperature interrupt with millies interrupt
OCR0B = 128;
ENABLE_TEMPERATURE_INTERRUPT();
#if HAS_AUTO_FAN_0
#if E0_AUTO_FAN_PIN == FAN1_PIN
SET_OUTPUT(E0_AUTO_FAN_PIN);
@ -1277,11 +1267,6 @@ void Temperature::init() {
#endif
#endif
// Use timer0 for temperature measurement
// Interleave temperature interrupt with millies interrupt
OCR0B = 128;
ENABLE_TEMPERATURE_INTERRUPT();
// Wait for temperature measurement to settle
delay(250);
@ -1792,24 +1777,14 @@ void Temperature::set_current_temp_raw() {
* - Step the babysteps value for each axis towards 0
* - For PINS_DEBUGGING, monitor and report endstop pins
* - For ENDSTOP_INTERRUPTS_FEATURE check endstops if flagged
* - Call planner.tick to count down its "ignore" time
*/
ISR(TIMER0_COMPB_vect) {
/**
* AVR has no hardware interrupt preemption, so emulate priorization
* and preemption of this ISR by all others by disabling the timer
* interrupt generation capability and reenabling global interrupts.
* Any interrupt can then interrupt this handler and preempt it.
* This ISR becomes the lowest priority one so the UART, Endstops
* and Stepper ISRs can all preempt it.
*/
DISABLE_TEMPERATURE_INTERRUPT();
sei();
HAL_TEMP_TIMER_ISR {
HAL_timer_isr_prologue(TEMP_TIMER_NUM);
Temperature::isr();
// Disable global interrupts and reenable this ISR
cli();
ENABLE_TEMPERATURE_INTERRUPT();
HAL_timer_isr_epilogue(TEMP_TIMER_NUM);
}
void Temperature::isr() {
@ -2107,13 +2082,6 @@ void Temperature::isr() {
* This gives each ADC 0.9765ms to charge up.
*/
#define SET_ADMUX_ADCSRA(pin) ADMUX = _BV(REFS0) | (pin & 0x07); SBI(ADCSRA, ADSC)
#ifdef MUX5
#define START_ADC(pin) if (pin > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#else
#define START_ADC(pin) ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#endif
switch (adc_sensor_state) {
case SensorsReady: {
@ -2133,25 +2101,25 @@ void Temperature::isr() {
#if HAS_TEMP_ADC_0
case PrepareTemp_0:
START_ADC(TEMP_0_PIN);
HAL_START_ADC(TEMP_0_PIN);
break;
case MeasureTemp_0:
raw_temp_value[0] += ADC;
raw_temp_value[0] += HAL_READ_ADC;
break;
#endif
#if HAS_HEATED_BED
case PrepareTemp_BED:
START_ADC(TEMP_BED_PIN);
HAL_START_ADC(TEMP_BED_PIN);
break;
case MeasureTemp_BED:
raw_temp_bed_value += ADC;
raw_temp_bed_value += HAL_READ_ADC;
break;
#endif
#if HAS_TEMP_CHAMBER
case PrepareTemp_CHAMBER:
START_ADC(TEMP_CHAMBER_PIN);
HAL_START_ADC(TEMP_CHAMBER_PIN);
break;
case MeasureTemp_CHAMBER:
raw_temp_chamber_value += ADC;
@ -2160,55 +2128,55 @@ void Temperature::isr() {
#if HAS_TEMP_ADC_1
case PrepareTemp_1:
START_ADC(TEMP_1_PIN);
HAL_START_ADC(TEMP_1_PIN);
break;
case MeasureTemp_1:
raw_temp_value[1] += ADC;
raw_temp_value[1] += HAL_READ_ADC;
break;
#endif
#if HAS_TEMP_ADC_2
case PrepareTemp_2:
START_ADC(TEMP_2_PIN);
HAL_START_ADC(TEMP_2_PIN);
break;
case MeasureTemp_2:
raw_temp_value[2] += ADC;
raw_temp_value[2] += HAL_READ_ADC;
break;
#endif
#if HAS_TEMP_ADC_3
case PrepareTemp_3:
START_ADC(TEMP_3_PIN);
HAL_START_ADC(TEMP_3_PIN);
break;
case MeasureTemp_3:
raw_temp_value[3] += ADC;
raw_temp_value[3] += HAL_READ_ADC;
break;
#endif
#if HAS_TEMP_ADC_4
case PrepareTemp_4:
START_ADC(TEMP_4_PIN);
HAL_START_ADC(TEMP_4_PIN);
break;
case MeasureTemp_4:
raw_temp_value[4] += ADC;
raw_temp_value[4] += HAL_READ_ADC;
break;
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
case Prepare_FILWIDTH:
START_ADC(FILWIDTH_PIN);
HAL_START_ADC(FILWIDTH_PIN);
break;
case Measure_FILWIDTH:
if (ADC > 102) { // Make sure ADC is reading > 0.5 volts, otherwise don't read.
if (HAL_READ_ADC > 102) { // Make sure ADC is reading > 0.5 volts, otherwise don't read.
raw_filwidth_value -= (raw_filwidth_value >> 7); // Subtract 1/128th of the raw_filwidth_value
raw_filwidth_value += ((unsigned long)ADC << 7); // Add new ADC reading, scaled by 128
raw_filwidth_value += ((unsigned long)HAL_READ_ADC << 7); // Add new ADC reading, scaled by 128
}
break;
#endif
#if ENABLED(ADC_KEYPAD)
case Prepare_ADC_KEY:
START_ADC(ADC_KEYPAD_PIN);
HAL_START_ADC(ADC_KEYPAD_PIN);
break;
case Measure_ADC_KEY:
if (ADCKey_count < 16) {
@ -2330,26 +2298,11 @@ void Temperature::isr() {
}
#endif // BABYSTEPPING
#if ENABLED(PINS_DEBUGGING)
extern bool endstop_monitor_flag;
// run the endstop monitor at 15Hz
static uint8_t endstop_monitor_count = 16; // offset this check from the others
if (endstop_monitor_flag) {
endstop_monitor_count += _BV(1); // 15 Hz
endstop_monitor_count &= 0x7F;
if (!endstop_monitor_count) endstop_monitor(); // report changes in endstop status
}
#endif
// Poll endstops state, if required
endstops.poll();
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
extern volatile uint8_t e_hit;
if (e_hit && ENDSTOPS_ENABLED) {
endstops.update(); // call endstop update routine
e_hit--;
}
#endif
// Periodically call the planner timer
planner.tick();
}
#if HAS_TEMP_SENSOR

View File

@ -257,7 +257,8 @@
z_position = end[Z_AXIS];
}
planner.buffer_segment(rx, ry, z_position + z0, e_position, feed_rate, extruder);
if (!planner.buffer_segment(rx, ry, z_position + z0, e_position, feed_rate, extruder))
break;
} //else printf("FIRST MOVE PRUNED ");
}
@ -314,7 +315,8 @@
e_position = end[E_AXIS];
z_position = end[Z_AXIS];
}
planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, feed_rate, extruder);
if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, feed_rate, extruder))
break;
current_yi += dyi;
yi_cnt--;
}
@ -337,7 +339,8 @@
z_position = end[Z_AXIS];
}
planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, feed_rate, extruder);
if (!planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, feed_rate, extruder))
break;
current_xi += dxi;
xi_cnt--;
}
@ -366,7 +369,7 @@
inline void _O2 ubl_buffer_segment_raw(const float (&in_raw)[XYZE], const float &fr) {
#if ENABLED(SKEW_CORRECTION)
float raw[XYZE] = { in_raw[X_AXIS], in_raw[Y_AXIS], in_raw[Z_AXIS], in_raw[E_AXIS] };
float raw[XYZE] = { in_raw[X_AXIS], in_raw[Y_AXIS], in_raw[Z_AXIS] };
planner.skew(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]);
#else
const float (&raw)[XYZE] = in_raw;
@ -438,7 +441,7 @@
uint16_t segments = lroundf(cartesian_xy_mm * (1.0 / (DELTA_SEGMENT_MIN_LENGTH))); // cartesian fixed segment length
#endif
NOLESS(segments, 1); // must have at least one segment
NOLESS(segments, 1U); // must have at least one segment
const float inv_segments = 1.0 / segments; // divide once, multiply thereafter
#if IS_SCARA // scale the feed rate from mm/s to degrees/s

View File

@ -2393,12 +2393,10 @@ void lcd_quick_feedback(const bool clear_buttons) {
void _lcd_do_nothing() {}
void _lcd_hard_stop() {
stepper.quick_stop();
const screenFunc_t old_screen = currentScreen;
currentScreen = _lcd_do_nothing;
while (planner.movesplanned()) idle();
planner.quick_stop();
currentScreen = old_screen;
stepper.cleaning_buffer_counter = 0;
set_current_from_steppers_for_axis(ALL_AXES);
sync_plan_position();
}
@ -3806,7 +3804,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
// M540 S - Abort on endstop hit when SD printing
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &stepper.abort_on_endstop_hit);
MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &planner.abort_on_endstop_hit);
#endif
END_MENU();