Browse Source

Tweaks to TMC26XStepper

Scott Lahteine 6 years ago
parent
commit
0d30ccf767
2 changed files with 22 additions and 45 deletions
  1. 20
    43
      Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp
  2. 2
    2
      Marlin/src/HAL/HAL_STM32F7/TMC2660.h

+ 20
- 43
Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp View File

127
  * dir_pin - the pin where the direction pin is connected
127
  * dir_pin - the pin where the direction pin is connected
128
  * step_pin - the pin where the step pin is connected
128
  * step_pin - the pin where the step pin is connected
129
  */
129
  */
130
-TMC26XStepper::TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor) {
130
+TMC26XStepper::TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor) {
131
   // We are not started yet
131
   // We are not started yet
132
   started = false;
132
   started = false;
133
 
133
 
165
   // Set a nice microstepping value
165
   // Set a nice microstepping value
166
   setMicrosteps(DEFAULT_MICROSTEPPING_VALUE);
166
   setMicrosteps(DEFAULT_MICROSTEPPING_VALUE);
167
   // Save the number of steps
167
   // Save the number of steps
168
-  this->number_of_steps = number_of_steps;
168
+  number_of_steps = in_steps;
169
 }
169
 }
170
 
170
 
171
 
171
 
389
  * any value in between will be mapped to the next smaller value
389
  * any value in between will be mapped to the next smaller value
390
  * 0 and 1 set the motor in full step mode
390
  * 0 and 1 set the motor in full step mode
391
  */
391
  */
392
-void TMC26XStepper::setMicrosteps(int16_t number_of_steps) {
393
-  long setting_pattern;
394
-  //poor mans log
395
-  if (number_of_steps >= 256) {
396
-    setting_pattern = 0;
397
-    microsteps = 256;
398
-  }
399
-  else if (number_of_steps >= 128) {
400
-    setting_pattern = 1;
401
-    microsteps = 128;
402
-  }
403
-  else if (number_of_steps >= 64) {
404
-    setting_pattern = 2;
405
-    microsteps = 64;
406
-  }
407
-  else if (number_of_steps >= 32) {
408
-    setting_pattern = 3;
409
-    microsteps = 32;
410
-  }
411
-  else if (number_of_steps >= 16) {
412
-    setting_pattern = 4;
413
-    microsteps = 16;
414
-  }
415
-  else if (number_of_steps >= 8) {
416
-    setting_pattern = 5;
417
-    microsteps = 8;
418
-  }
419
-  else if (number_of_steps >= 4) {
420
-    setting_pattern = 6;
421
-    microsteps = 4;
422
-  }
423
-  else if (number_of_steps >= 2) {
424
-    setting_pattern = 7;
425
-    microsteps = 2;
426
-    //1 and 0 lead to full step
427
-  }
428
-  else if (number_of_steps <= 1) {
429
-    setting_pattern = 8;
430
-    microsteps = 1;
431
-  }
392
+void TMC26XStepper::setMicrosteps(const int16_t in_steps) {
393
+  uint16_t setting_pattern;
394
+
395
+       if (in_steps >= 256) setting_pattern = 0;
396
+  else if (in_steps >= 128) setting_pattern = 1;
397
+  else if (in_steps >=  64) setting_pattern = 2;
398
+  else if (in_steps >=  32) setting_pattern = 3;
399
+  else if (in_steps >=  16) setting_pattern = 4;
400
+  else if (in_steps >=   8) setting_pattern = 5;
401
+  else if (in_steps >=   4) setting_pattern = 6;
402
+  else if (in_steps >=   2) setting_pattern = 7;
403
+  else if (in_steps <=   1) setting_pattern = 8; // 1 and 0 lead to full step
404
+
405
+  microsteps = _BV(8 - setting_pattern);
406
+
432
   #ifdef TMC_DEBUG0 // crashes
407
   #ifdef TMC_DEBUG0 // crashes
433
     //SERIAL_PRINTF("Microstepping: ");
408
     //SERIAL_PRINTF("Microstepping: ");
434
     SERIAL_ECHOPAIR("\n Microstepping: ", microsteps);
409
     SERIAL_ECHOPAIR("\n Microstepping: ", microsteps);
435
   #endif
410
   #endif
411
+
436
   // Delete the old value
412
   // Delete the old value
437
-  this->driver_control_register_value &= 0xFFFF0UL;
413
+  this->driver_control_register_value &= 0x000FFFF0UL;
414
+
438
   // Set the new value
415
   // Set the new value
439
   this->driver_control_register_value |= setting_pattern;
416
   this->driver_control_register_value |= setting_pattern;
440
 
417
 

+ 2
- 2
Marlin/src/HAL/HAL_STM32F7/TMC2660.h View File

119
      * You can select a different stepping with setMicrosteps() to aa different value.
119
      * You can select a different stepping with setMicrosteps() to aa different value.
120
      * \sa start(), setMicrosteps()
120
      * \sa start(), setMicrosteps()
121
      */
121
      */
122
-    TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor=100); //resistor=150
122
+    TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor=100); //resistor=150
123
 
123
 
124
     /*!
124
     /*!
125
      * \brief configures and starts the TMC26X stepper driver. Before you called this function the stepper driver is in nonfunctional mode.
125
      * \brief configures and starts the TMC26X stepper driver. Before you called this function the stepper driver is in nonfunctional mode.
163
      * If you give any other value it will be rounded to the next smaller number (3 would give a microstepping of 2).
163
      * If you give any other value it will be rounded to the next smaller number (3 would give a microstepping of 2).
164
      * You can always check the current microstepping with getMicrosteps().
164
      * You can always check the current microstepping with getMicrosteps().
165
      */
165
      */
166
-    void setMicrosteps(int16_t number_of_steps);
166
+    void setMicrosteps(const int16_t in_steps);
167
 
167
 
168
     /*!
168
     /*!
169
      * \brief returns the effective current number of microsteps selected.
169
      * \brief returns the effective current number of microsteps selected.

Loading…
Cancel
Save