Keep "astyled" elements in stepper.*
This commit is contained in:
@@ -37,7 +37,7 @@
|
||||
//===========================================================================
|
||||
//============================= public variables ============================
|
||||
//===========================================================================
|
||||
block_t *current_block; // A pointer to the block currently being traced
|
||||
block_t* current_block; // A pointer to the block currently being traced
|
||||
|
||||
|
||||
//===========================================================================
|
||||
@@ -408,14 +408,14 @@ inline void update_endstops() {
|
||||
#else // !Z_DUAL_ENDSTOPS
|
||||
|
||||
UPDATE_ENDSTOP(Z, MIN);
|
||||
|
||||
#endif // !Z_DUAL_ENDSTOPS
|
||||
#endif // Z_MIN_PIN
|
||||
|
||||
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
|
||||
UPDATE_ENDSTOP(Z, MIN_PROBE);
|
||||
|
||||
if (TEST_ENDSTOP(Z_MIN_PROBE))
|
||||
{
|
||||
if (TEST_ENDSTOP(Z_MIN_PROBE)) {
|
||||
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
|
||||
endstop_hit_bits |= BIT(Z_MIN_PROBE);
|
||||
}
|
||||
@@ -495,17 +495,17 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
|
||||
if (step_rate < (F_CPU / 500000)) step_rate = (F_CPU / 500000);
|
||||
step_rate -= (F_CPU / 500000); // Correct for minimal speed
|
||||
if (step_rate >= (8 * 256)) { // higher step rate
|
||||
unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
|
||||
unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate >> 8)][0];
|
||||
unsigned char tmp_step_rate = (step_rate & 0x00ff);
|
||||
unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
|
||||
unsigned short gain = (unsigned short)pgm_read_word_near(table_address + 2);
|
||||
MultiU16X8toH16(timer, tmp_step_rate, gain);
|
||||
timer = (unsigned short)pgm_read_word_near(table_address) - timer;
|
||||
}
|
||||
else { // lower step rates
|
||||
unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
|
||||
table_address += ((step_rate)>>1) & 0xfffc;
|
||||
table_address += ((step_rate) >> 1) & 0xfffc;
|
||||
timer = (unsigned short)pgm_read_word_near(table_address);
|
||||
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
|
||||
timer -= (((unsigned short)pgm_read_word_near(table_address + 2) * (unsigned char)(step_rate & 0x0007)) >> 3);
|
||||
}
|
||||
if (timer < 100) { timer = 100; MYSERIAL.print(MSG_STEPPER_TOO_HIGH); MYSERIAL.println(step_rate); }//(20kHz this should never happen)
|
||||
return timer;
|
||||
@@ -704,16 +704,18 @@ ISR(TIMER1_COMPA_vect) {
|
||||
timer = calc_timer(acc_step_rate);
|
||||
OCR1A = timer;
|
||||
acceleration_time += timer;
|
||||
|
||||
#if ENABLED(ADVANCE)
|
||||
for(int8_t i=0; i < step_loops; i++) {
|
||||
|
||||
for (int8_t i = 0; i < step_loops; i++) {
|
||||
advance += advance_rate;
|
||||
}
|
||||
//if (advance > current_block->advance) advance = current_block->advance;
|
||||
// Do E steps + advance steps
|
||||
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
|
||||
old_advance = advance >>8;
|
||||
e_steps[current_block->active_extruder] += ((advance >> 8) - old_advance);
|
||||
old_advance = advance >> 8;
|
||||
|
||||
#endif
|
||||
#endif //ADVANCE
|
||||
}
|
||||
else if (step_events_completed > (unsigned long)current_block->decelerate_after) {
|
||||
MultiU24X32toH16(step_rate, deceleration_time, current_block->acceleration_rate);
|
||||
@@ -734,13 +736,13 @@ ISR(TIMER1_COMPA_vect) {
|
||||
OCR1A = timer;
|
||||
deceleration_time += timer;
|
||||
#if ENABLED(ADVANCE)
|
||||
for(int8_t i=0; i < step_loops; i++) {
|
||||
for (int8_t i = 0; i < step_loops; i++) {
|
||||
advance -= advance_rate;
|
||||
}
|
||||
if (advance < final_advance) advance = final_advance;
|
||||
// Do E steps + advance steps
|
||||
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
|
||||
old_advance = advance >>8;
|
||||
e_steps[current_block->active_extruder] += ((advance >> 8) - old_advance);
|
||||
old_advance = advance >> 8;
|
||||
#endif //ADVANCE
|
||||
}
|
||||
else {
|
||||
@@ -749,7 +751,7 @@ ISR(TIMER1_COMPA_vect) {
|
||||
step_loops = step_loops_nominal;
|
||||
}
|
||||
|
||||
OCR1A = (OCR1A < (TCNT1 +16)) ? (TCNT1 + 16) : OCR1A;
|
||||
OCR1A = (OCR1A < (TCNT1 + 16)) ? (TCNT1 + 16) : OCR1A;
|
||||
|
||||
// If current block is finished, reset pointer
|
||||
if (step_events_completed >= current_block->step_event_count) {
|
||||
@@ -763,12 +765,11 @@ ISR(TIMER1_COMPA_vect) {
|
||||
unsigned char old_OCR0A;
|
||||
// Timer interrupt for E. e_steps is set in the main routine;
|
||||
// Timer 0 is shared with millies
|
||||
ISR(TIMER0_COMPA_vect)
|
||||
{
|
||||
ISR(TIMER0_COMPA_vect) {
|
||||
old_OCR0A += 52; // ~10kHz interrupt (250000 / 26 = 9615kHz)
|
||||
OCR0A = old_OCR0A;
|
||||
// Set E direction (Depends on E direction + advance)
|
||||
for(unsigned char i=0; i<4;i++) {
|
||||
for (unsigned char i = 0; i < 4; i++) {
|
||||
if (e_steps[0] != 0) {
|
||||
E0_STEP_WRITE(INVERT_E_STEP_PIN);
|
||||
if (e_steps[0] < 0) {
|
||||
@@ -827,7 +828,6 @@ ISR(TIMER1_COMPA_vect) {
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
}
|
||||
#endif // ADVANCE
|
||||
@@ -1032,15 +1032,14 @@ void st_init() {
|
||||
TCCR1A &= ~BIT(WGM10);
|
||||
|
||||
// output mode = 00 (disconnected)
|
||||
TCCR1A &= ~(3<<COM1A0);
|
||||
TCCR1A &= ~(3<<COM1B0);
|
||||
|
||||
TCCR1A &= ~(3 << COM1A0);
|
||||
TCCR1A &= ~(3 << COM1B0);
|
||||
// Set the timer pre-scaler
|
||||
// Generally we use a divider of 8, resulting in a 2MHz timer
|
||||
// frequency on a 16MHz MCU. If you are going to change this, be
|
||||
// sure to regenerate speed_lookuptable.h with
|
||||
// create_speed_lookuptable.py
|
||||
TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10);
|
||||
TCCR1B = (TCCR1B & ~(0x07 << CS10)) | (2 << CS10);
|
||||
|
||||
OCR1A = 0x4000;
|
||||
TCNT1 = 0;
|
||||
@@ -1067,7 +1066,7 @@ void st_init() {
|
||||
*/
|
||||
void st_synchronize() { while (blocks_queued()) idle(); }
|
||||
|
||||
void st_set_position(const long &x, const long &y, const long &z, const long &e) {
|
||||
void st_set_position(const long& x, const long& y, const long& z, const long& e) {
|
||||
CRITICAL_SECTION_START;
|
||||
count_position[X_AXIS] = x;
|
||||
count_position[Y_AXIS] = y;
|
||||
@@ -1076,7 +1075,7 @@ void st_set_position(const long &x, const long &y, const long &z, const long &e)
|
||||
CRITICAL_SECTION_END;
|
||||
}
|
||||
|
||||
void st_set_e_position(const long &e) {
|
||||
void st_set_e_position(const long& e) {
|
||||
CRITICAL_SECTION_START;
|
||||
count_position[E_AXIS] = e;
|
||||
CRITICAL_SECTION_END;
|
||||
@@ -1126,7 +1125,7 @@ void quickStop() {
|
||||
_APPLY_DIR(AXIS, old_pin); \
|
||||
}
|
||||
|
||||
switch(axis) {
|
||||
switch (axis) {
|
||||
|
||||
case X_AXIS:
|
||||
BABYSTEP_AXIS(x, X, false);
|
||||
@@ -1153,9 +1152,9 @@ void quickStop() {
|
||||
old_y_dir_pin = Y_DIR_READ,
|
||||
old_z_dir_pin = Z_DIR_READ;
|
||||
//setup new step
|
||||
X_DIR_WRITE(INVERT_X_DIR^z_direction);
|
||||
Y_DIR_WRITE(INVERT_Y_DIR^z_direction);
|
||||
Z_DIR_WRITE(INVERT_Z_DIR^z_direction);
|
||||
X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
|
||||
Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
|
||||
Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
|
||||
//perform step
|
||||
X_STEP_WRITE(!INVERT_X_STEP_PIN);
|
||||
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
|
||||
@@ -1182,10 +1181,10 @@ void quickStop() {
|
||||
// From Arduino DigitalPotControl example
|
||||
void digitalPotWrite(int address, int value) {
|
||||
#if HAS_DIGIPOTSS
|
||||
digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip
|
||||
digitalWrite(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip
|
||||
SPI.transfer(address); // send in the address and value via SPI:
|
||||
SPI.transfer(value);
|
||||
digitalWrite(DIGIPOTSS_PIN,HIGH); // take the SS pin high to de-select the chip:
|
||||
digitalWrite(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip:
|
||||
//delay(10);
|
||||
#else
|
||||
UNUSED(address);
|
||||
@@ -1202,7 +1201,7 @@ void digipot_init() {
|
||||
pinMode(DIGIPOTSS_PIN, OUTPUT);
|
||||
for (int i = 0; i <= 4; i++) {
|
||||
//digitalPotWrite(digipot_ch[i], digipot_motor_current[i]);
|
||||
digipot_current(i,digipot_motor_current[i]);
|
||||
digipot_current(i, digipot_motor_current[i]);
|
||||
}
|
||||
#endif
|
||||
#ifdef MOTOR_CURRENT_PWM_XY_PIN
|
||||
@@ -1222,7 +1221,7 @@ void digipot_current(uint8_t driver, int current) {
|
||||
const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
|
||||
digitalPotWrite(digipot_ch[driver], current);
|
||||
#elif defined(MOTOR_CURRENT_PWM_XY_PIN)
|
||||
switch(driver) {
|
||||
switch (driver) {
|
||||
case 0: analogWrite(MOTOR_CURRENT_PWM_XY_PIN, 255L * current / MOTOR_CURRENT_PWM_RANGE); break;
|
||||
case 1: analogWrite(MOTOR_CURRENT_PWM_Z_PIN, 255L * current / MOTOR_CURRENT_PWM_RANGE); break;
|
||||
case 2: analogWrite(MOTOR_CURRENT_PWM_E_PIN, 255L * current / MOTOR_CURRENT_PWM_RANGE); break;
|
||||
@@ -1235,19 +1234,19 @@ void digipot_current(uint8_t driver, int current) {
|
||||
|
||||
void microstep_init() {
|
||||
#if HAS_MICROSTEPS_E1
|
||||
pinMode(E1_MS1_PIN,OUTPUT);
|
||||
pinMode(E1_MS2_PIN,OUTPUT);
|
||||
pinMode(E1_MS1_PIN, OUTPUT);
|
||||
pinMode(E1_MS2_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
#if HAS_MICROSTEPS
|
||||
pinMode(X_MS1_PIN,OUTPUT);
|
||||
pinMode(X_MS2_PIN,OUTPUT);
|
||||
pinMode(Y_MS1_PIN,OUTPUT);
|
||||
pinMode(Y_MS2_PIN,OUTPUT);
|
||||
pinMode(Z_MS1_PIN,OUTPUT);
|
||||
pinMode(Z_MS2_PIN,OUTPUT);
|
||||
pinMode(E0_MS1_PIN,OUTPUT);
|
||||
pinMode(E0_MS2_PIN,OUTPUT);
|
||||
pinMode(X_MS1_PIN, OUTPUT);
|
||||
pinMode(X_MS2_PIN, OUTPUT);
|
||||
pinMode(Y_MS1_PIN, OUTPUT);
|
||||
pinMode(Y_MS2_PIN, OUTPUT);
|
||||
pinMode(Z_MS1_PIN, OUTPUT);
|
||||
pinMode(Z_MS2_PIN, OUTPUT);
|
||||
pinMode(E0_MS1_PIN, OUTPUT);
|
||||
pinMode(E0_MS2_PIN, OUTPUT);
|
||||
const uint8_t microstep_modes[] = MICROSTEP_MODES;
|
||||
for (uint16_t i = 0; i < COUNT(microstep_modes); i++)
|
||||
microstep_mode(i, microstep_modes[i]);
|
||||
@@ -1255,7 +1254,7 @@ void microstep_init() {
|
||||
}
|
||||
|
||||
void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
|
||||
if (ms1 >= 0) switch(driver) {
|
||||
if (ms1 >= 0) switch (driver) {
|
||||
case 0: digitalWrite(X_MS1_PIN, ms1); break;
|
||||
case 1: digitalWrite(Y_MS1_PIN, ms1); break;
|
||||
case 2: digitalWrite(Z_MS1_PIN, ms1); break;
|
||||
@@ -1264,7 +1263,7 @@ void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
|
||||
case 4: digitalWrite(E1_MS1_PIN, ms1); break;
|
||||
#endif
|
||||
}
|
||||
if (ms2 >= 0) switch(driver) {
|
||||
if (ms2 >= 0) switch (driver) {
|
||||
case 0: digitalWrite(X_MS2_PIN, ms2); break;
|
||||
case 1: digitalWrite(Y_MS2_PIN, ms2); break;
|
||||
case 2: digitalWrite(Z_MS2_PIN, ms2); break;
|
||||
@@ -1276,12 +1275,12 @@ void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
|
||||
}
|
||||
|
||||
void microstep_mode(uint8_t driver, uint8_t stepping_mode) {
|
||||
switch(stepping_mode) {
|
||||
case 1: microstep_ms(driver,MICROSTEP1); break;
|
||||
case 2: microstep_ms(driver,MICROSTEP2); break;
|
||||
case 4: microstep_ms(driver,MICROSTEP4); break;
|
||||
case 8: microstep_ms(driver,MICROSTEP8); break;
|
||||
case 16: microstep_ms(driver,MICROSTEP16); break;
|
||||
switch (stepping_mode) {
|
||||
case 1: microstep_ms(driver, MICROSTEP1); break;
|
||||
case 2: microstep_ms(driver, MICROSTEP2); break;
|
||||
case 4: microstep_ms(driver, MICROSTEP4); break;
|
||||
case 8: microstep_ms(driver, MICROSTEP8); break;
|
||||
case 16: microstep_ms(driver, MICROSTEP16); break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -60,8 +60,8 @@ void st_init();
|
||||
void st_synchronize();
|
||||
|
||||
// Set current position in steps
|
||||
void st_set_position(const long &x, const long &y, const long &z, const long &e);
|
||||
void st_set_e_position(const long &e);
|
||||
void st_set_position(const long& x, const long& y, const long& z, const long& e);
|
||||
void st_set_e_position(const long& e);
|
||||
|
||||
// Get current position in steps
|
||||
long st_get_position(uint8_t axis);
|
||||
@@ -83,7 +83,7 @@ void checkStepperErrors(); //Print errors detected by the stepper
|
||||
|
||||
void finishAndDisableSteppers();
|
||||
|
||||
extern block_t *current_block; // A pointer to the block currently being traced
|
||||
extern block_t* current_block; // A pointer to the block currently being traced
|
||||
|
||||
void quickStop();
|
||||
|
||||
@@ -102,7 +102,7 @@ void microstep_readings();
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
|
||||
void babystep(const uint8_t axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
Reference in New Issue
Block a user