uStepper S
uStepperS.cpp
Go to the documentation of this file.
1 /********************************************************************************************
2 * File: uStepperS.cpp *
3 * Version: 2.2.0 *
4 * Date: September 22nd, 2020 *
5 * Authors: Thomas Hørring Olsen *
6 * Emil Jacobsen *
7 * *
8 *********************************************************************************************
9 * (C) 2020 *
10 * *
11 * uStepper ApS *
12 * www.ustepper.com *
13 * administration@ustepper.com *
14 * *
15 * The code contained in this file is released under the following open source license: *
16 * *
17 * Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International *
18 * *
19 * The code in this file is provided without warranty of any kind - use at own risk! *
20 * neither uStepper ApS nor the author, can be held responsible for any damage *
21 * caused by the use of the code contained in this file ! *
22 * *
23 ********************************************************************************************/
33 #include <uStepperS.h>
35 
37 {
38  pointer = this;
39 
40  this->microSteps = 256;
41  this->init();
42 
43  this->setMaxAcceleration(2000.0);
44  this->setMaxDeceleration(2000.0);
45  this->setMaxVelocity(100.0);
46 }
47 
48 uStepperS::uStepperS(float acceleration, float velocity)
49 {
50  pointer = this;
51  this->microSteps = 256;
52  this->init();
53 
54  this->setMaxAcceleration(acceleration);
55  this->setMaxVelocity(velocity);
56 }
57 
58 
59 void uStepperS::init( void ){
60 
61 
62  this->pidDisabled = 1;
63  /* Set CS, MOSI, SCK and DRV_ENN as Output */
64  DDRC = (1<<SCK1)|(1<<MOSI_ENC);
65  DDRD = (1<<DRV_ENN)|(1<<SD_MODE)|(1<<CS_ENCODER);
66  DDRE = (1<<MOSI1)|(1<<CS_DRIVER);
67 
68  PORTD |= (1 << DRV_ENN); // Set DRV_ENN HIGH, while configuring
69  PORTD &= ~(1 << SD_MODE); // Set SD_MODE LOW
70 
71  /*
72  * ---- Global SPI1 configuration ----
73  * SPE = 1: SPI enabled
74  * MSTR = 1: Master
75  * SPR0 = 0 & SPR1 = 0: fOSC/4 = 4Mhz
76  */
77  SPCR1 = (1<<SPE1)|(1<<MSTR1);
78 
79  driver.init( this );
80  encoder.init( this );
81  PORTD &= ~(1 << DRV_ENN); // Set DRV_ENN LOW
82 }
83 
84 bool uStepperS::getMotorState(uint8_t statusType)
85 {
86  this->driver.readMotorStatus();
87  if(this->driver.status & statusType)
88  {
89  return 0;
90  }
91  return 1;
92 }
93 
95 {
96  int32_t velocity = this->driver.getVelocity();
97 
98  return (float)velocity * this->velToRpm;
99 }
100 
101 void uStepperS::checkOrientation(float distance)
102 {
103  float startAngle;
104  uint8_t inverted = 0;
105  uint8_t noninverted = 0;
106  this->disablePid();
107  this->shaftDir = 0;
108  this->driver.setShaftDirection(this->shaftDir);
109 
110  startAngle = this->encoder.getAngleMoved();
111  this->moveAngle(distance);
112 
113  while(this->getMotorState());
114 
115  startAngle -= distance/2.0;
116  if(this->encoder.getAngleMoved() < startAngle)
117  {
118  inverted++;
119  }
120  else
121  {
122  noninverted++;
123  }
124 
125  startAngle = this->encoder.getAngleMoved();
126  this->moveAngle(-distance);
127 
128  while(this->getMotorState());
129 
130  startAngle += distance/2.0;
131  if(this->encoder.getAngleMoved() > startAngle)
132  {
133  inverted++;
134  }
135  else
136  {
137  noninverted++;
138  }
139 
140  startAngle = this->encoder.getAngleMoved();
141  this->moveAngle(distance);
142 
143  while(this->getMotorState());
144 
145  startAngle -= distance/2.0;
146  if(this->encoder.getAngleMoved() < startAngle)
147  {
148  inverted++;
149  }
150  else
151  {
152  noninverted++;
153  }
154 
155  this->moveAngle(-distance);
156 
157  while(this->getMotorState());
158 
159  if(inverted > noninverted)
160  {
161  this->shaftDir = 1;
162  this->driver.setShaftDirection(this->shaftDir);
163  }
164  this->enablePid();
165 }
166 
167 void uStepperS::setup( uint8_t mode,
168  uint16_t stepsPerRevolution,
169  float pTerm,
170  float iTerm,
171  float dTerm,
172  uint16_t dropinStepSize,
173  bool setHome,
174  uint8_t invert,
175  uint8_t runCurrent,
176  uint8_t holdCurrent)
177 {
178  dropinCliSettings_t tempSettings;
179  this->pidDisabled = 1;
180  // Should setup mode etc. later
181  this->mode = mode;
182  this->fullSteps = stepsPerRevolution;
183  this->dropinStepSize = 256/dropinStepSize;
184  this->angleToStep = (float)this->fullSteps * (float)this->microSteps / 360.0;
185  this->rpmToVelocity = (float)(279620.267 * fullSteps * microSteps)/(CLOCKFREQ);
186  this->stepsPerSecondToRPM = 60.0/(this->microSteps*this->fullSteps);
187  this->RPMToStepsPerSecond = (this->microSteps*this->fullSteps)/60.0;
188 
189 
190  this->stepTime = 16777216.0/CLOCKFREQ; // 2^24/CLOCKFREQ
191  this->rpmToVel = (this->fullSteps*this->microSteps)/(60.0/this->stepTime);
192  this->velToRpm = 1.0/this->rpmToVel;
193 
194  this->init();
195 
196  this->driver.setDeceleration( (uint32_t)( this->maxDeceleration ) );
197  this->driver.setAcceleration( (uint32_t)(this->maxAcceleration ) );
198 
199  this->setCurrent(0.0);
200  this->setHoldCurrent(0.0);
201 
202  this->setCurrent(40.0);
203  this->setHoldCurrent(0.0);
204 
205  this->encoder.Beta=5;
206  if(this->mode)
207  {
208  if(this->mode == DROPIN)
209  {
210  //Set Enable, Step and Dir signal pins from 3dPrinter controller as inputs
211  this->encoder.Beta = 2;
212  pinMode(2,INPUT);
213  pinMode(3,INPUT);
214  pinMode(4,INPUT);
215  //Enable internal pull-up resistors on the above pins
216  digitalWrite(2,HIGH);
217  digitalWrite(3,HIGH);
218  digitalWrite(4,HIGH);
219  delay(10000);
220  attachInterrupt(0, interrupt0, FALLING);
221  attachInterrupt(1, interrupt1, CHANGE);
222  this->driver.setDeceleration( 0xFFFE );
223  this->driver.setAcceleration( 0xFFFE );
224  Serial.begin(9600);
225 
226  tempSettings.P.f = pTerm;
227  tempSettings.I.f = iTerm;
228  tempSettings.D.f = dTerm;
229  tempSettings.invert = invert;
230  tempSettings.runCurrent = runCurrent;
231  tempSettings.holdCurrent = holdCurrent;
232  tempSettings.checksum = this->dropinSettingsCalcChecksum(&tempSettings);
233 
234  if(tempSettings.checksum != EEPROM.read(sizeof(dropinCliSettings_t)))
235  {
236  this->dropinSettings = tempSettings;
237  this->saveDropinSettings();
238  EEPROM.put(sizeof(dropinCliSettings_t),this->dropinSettings.checksum);
239  this->loadDropinSettings();
240  }
241  else
242  {
243  if(!this->loadDropinSettings())
244  {
245  this->dropinSettings = tempSettings;
246  this->saveDropinSettings();
247  EEPROM.put(sizeof(dropinCliSettings_t),this->dropinSettings.checksum);
248  this->loadDropinSettings();
249  }
250  }
251 
252 
253  this->dropinPrintHelp();
254  }
255  else
256  {
257  this->encoder.Beta = 4;
258  }
259  }
260 
261  if(setHome == true){
262  encoder.setHome();
263  }
264 
265  this->pidDisabled = 0;
266 
267  DDRB |= (1 << 4);
268 }
269 
270 void uStepperS::moveSteps( int32_t steps )
271 {
272  this->driver.setDeceleration( (uint16_t)( this->maxDeceleration ) );
273  this->driver.setAcceleration( (uint16_t)(this->maxAcceleration ) );
274  this->driver.setVelocity( (uint32_t)( this->maxVelocity ) );
275 
276  // Get current position
277  int32_t current = this->driver.getPosition();
278 
279  // Set new position
280  this->driver.setPosition( current + steps);
281 }
282 
283 
284 
285 void uStepperS::moveAngle( float angle )
286 {
287  int32_t steps;
288 
289  if(angle < 0.0)
290  {
291  steps = (int32_t)((angle * angleToStep) - 0.5);
292  this->moveSteps( steps );
293  }
294  else
295  {
296  steps = (int32_t)((angle * angleToStep) + 0.5);
297  this->moveSteps( steps );
298  }
299 }
300 
301 
302 void uStepperS::moveToAngle( float angle )
303 {
304  float diff;
305  int32_t steps;
306 
307  diff = angle - this->angleMoved();
308  steps = (int32_t)( (abs(diff) * angleToStep) + 0.5);
309 
310  if(diff < 0.0)
311  {
312  this->moveSteps( -steps );
313  }
314  else
315  {
316  this->moveSteps( steps );
317  }
318 }
319 
320 void uStepperS::enableStallguard( int8_t threshold, bool stopOnStall, float rpm )
321 {
322  this->clearStall();
323  this->stallThreshold = threshold;
324  this->stallStop = stopOnStall;
325 
326  pointer->driver.enableStallguard( threshold, stopOnStall, rpm);
327 
328  this->stallEnabled = true;
329 }
330 
332 {
333  pointer->driver.disableStallguard();
334 
335  this->stallEnabled = false;
336 }
337 
339 {
340  pointer->driver.clearStall();
341 }
342 
344 {
345  return this->isStalled( this->stallThreshold );
346 }
347 
348 bool uStepperS::isStalled( int8_t threshold )
349 {
350  // If the threshold is different from what is configured..
351  if( threshold != this->stallThreshold || this->stallEnabled == false ){
352  // Reconfigure stallguard
353  this->enableStallguard( threshold, this->stallStop, 10 );
354  }
355 
356  int32_t stats = pointer->driver.readRegister(RAMP_STAT);
357 
358  // Only interested in 'status_sg', with bit position 13 (last bit in RAMP_STAT).
359  return ( stats >> 13 );
360 }
361 
362 void uStepperS::setBrakeMode( uint8_t mode, float brakeCurrent )
363 {
364  int32_t registerContent = this->driver.readRegister(PWMCONF);
365  registerContent &= ~(3UL << 20);
366  if(mode == FREEWHEELBRAKE)
367  {
368  this->setHoldCurrent(0.0);
369  this->driver.writeRegister( PWMCONF, PWM_AUTOSCALE(1) | PWM_GRAD(1) | PWM_AMPL(128) | PWM_FREQ(0) | FREEWHEEL(1) );
370  }
371  else if(mode == COOLBRAKE)
372  {
373  this->setHoldCurrent(0.0);
374  this->driver.writeRegister( PWMCONF, PWM_AUTOSCALE(1) | PWM_GRAD(1) | PWM_AMPL(128) | PWM_FREQ(0) | FREEWHEEL(2) );
375  }
376  else
377  {
378  this->setHoldCurrent(brakeCurrent);
379  this->driver.writeRegister( PWMCONF, PWM_AUTOSCALE(1) | PWM_GRAD(1) | PWM_AMPL(128) | PWM_FREQ(0) | FREEWHEEL(0) );
380  }
381 }
382 
383 void uStepperS::setRPM( float rpm)
384 {
385  int32_t velocityDir = rpmToVelocity * rpm;
386 
387  if(velocityDir > 0){
388  driver.setDirection(1);
389  }else{
390  driver.setDirection(0);
391  }
392 
393  // The velocity cannot be signed
394  uint32_t velocity = abs(velocityDir);
395 
396  driver.setVelocity( (uint32_t)velocity );
397 }
398 
399 
400 void uStepperS::setSPIMode( uint8_t mode ){
401 
402  switch(mode){
403  case 2:
404  SPCR1 |= (1<<CPOL1); // Set CPOL HIGH = 1
405  SPCR1 &= ~(1<<CPHA1); // Set CPHA LOW = 0
406  break;
407 
408  case 3:
409  SPCR1 |= (1<<CPOL1); // Set CPOL HIGH = 1
410  SPCR1 |= (1<<CPHA1); // Set CPHA HIGH = 1
411  break;
412  }
413 }
414 
415 uint8_t uStepperS::SPI(uint8_t data){
416 
417  SPDR1 = data;
418 
419  // Wait for transmission complete
420  while(!( SPSR1 & (1 << SPIF1) ));
421 
422  return SPDR1;
423 
424 }
425 
426 void uStepperS::setMaxVelocity( float velocity )
427 {
428  velocity *= (float)this->microSteps;
429  velocity = abs(velocity)*VELOCITYCONVERSION;
430 
431  this->maxVelocity = velocity;
432 
433  // Steps per second, has to be converted to microsteps
434  this->driver.setVelocity( (uint32_t)( this->maxVelocity ) );
435 }
436 
437 void uStepperS::setMaxAcceleration( float acceleration )
438 {
439  acceleration *= (float)this->microSteps;
440  acceleration = abs(acceleration) * ACCELERATIONCONVERSION;
441 
442  this->maxAcceleration = acceleration;
443 
444 
445  // Steps per second, has to be converted to microsteps
446  this->driver.setAcceleration( (uint32_t)(this->maxAcceleration ) );
447 }
448 
449 void uStepperS::setMaxDeceleration( float deceleration )
450 {
451  deceleration *= (float)this->microSteps;
452  deceleration = abs(deceleration) * ACCELERATIONCONVERSION;
453 
454  this->maxDeceleration = deceleration;
455 
456  // Steps per second, has to be converted to microsteps
457  this->driver.setDeceleration( (uint32_t)(this->maxDeceleration ) );
458 }
459 
460 void uStepperS::setCurrent( double current )
461 {
462  if( current <= 100.0 && current >= 0.0){
463  // The current needs to be in the range of 0-31
464  this->driver.current = ceil(0.31 * current);
465  }else{
466  // If value is out of range, set default
467  this->driver.current = 16;
468  }
469 
471 }
472 
473 void uStepperS::setHoldCurrent( double current )
474 {
475  // The current needs to be in the range of 0-31
476  if( current <= 100.0 && current >= 0.0){
477  // The current needs to be in the range of 0-31
478  this->driver.holdCurrent = ceil(0.31 * current);
479  }else{
480  // If value is out of range, set default
481  this->driver.holdCurrent = 16;
482  }
483 
485 }
486 
487 void uStepperS::runContinous( bool direction )
488 {
489  this->driver.setDeceleration( (uint32_t)( this->maxDeceleration ) );
490  this->driver.setAcceleration( (uint32_t)(this->maxAcceleration ) );
491  this->driver.setVelocity( (uint32_t)( this->maxVelocity ) );
492 
493  // Make sure we use velocity mode
495 
496  // Set the direction
497  this->driver.setDirection( direction );
498 }
499 
500 float uStepperS::angleMoved ( void )
501 {
502  return this->encoder.getAngleMoved();
503 }
504 
505 void uStepperS::stop( bool mode){
506 
507  if(mode == HARD)
508  {
509  this->driver.setDeceleration( 0xFFFE );
510  this->driver.setAcceleration( 0xFFFE );
511  this->setRPM(0);
512  while(this->driver.readRegister(VACTUAL) != 0);
513  this->driver.setDeceleration( (uint32_t)( this->maxDeceleration ) );
514  this->driver.setAcceleration( (uint32_t)(this->maxAcceleration ) );
515  }
516  else
517  {
518  this->setRPM(0);
519  }
520 }
521 
522 void uStepperS::filterSpeedPos(posFilter_t *filter, int32_t steps)
523 {
524  if(this->mode != DROPIN)
525  {
526  filter->posEst += filter->velEst * ENCODERINTPERIOD * 0.5f;
527  }
528  else
529  {
530  filter->posEst += filter->velEst * ENCODERINTPERIOD;
531  }
532 
533 
534  filter->posError = (float)steps - filter->posEst;
535  if(this->mode != DROPIN)
536  {
537  filter->velIntegrator += filter->posError * PULSEFILTERKI * 0.5f;
538  }
539  else
540  {
541  filter->velIntegrator += filter->posError * PULSEFILTERKI;
542  }
543  filter->velEst = (filter->posError * PULSEFILTERKP) + filter->velIntegrator;
544 }
545 
546 void interrupt1(void)
547 {
548  if(PIND & 0x04)
549  {
550  PORTD |= (1 << 4);
551  }
552  else
553  {
554  PORTD &= ~(1 << 4);
555  }
556 }
557 
558 void interrupt0(void)
559 {
560  if(PIND & 0x04)
561  {
562  PORTD |= (1 << 4);
563  }
564  else
565  {
566  PORTD &= ~(1 << 4);
567  }
568  if((PINB & (0x08))) //CCW
569  {
571  {
572  pointer->stepCnt-=pointer->dropinStepSize; //DIR is set to CCW, therefore we subtract 1 step from step count (negative values = number of steps in CCW direction from initial postion)
573  }
574  else
575  {
576  pointer->stepCnt+=pointer->dropinStepSize; //DIR is set to CW, therefore we add 1 step to step count (positive values = number of steps in CW direction from initial postion)
577  }
578 
579  }
580  else //CW
581  {
583  {
584  pointer->stepCnt+=pointer->dropinStepSize; //DIR is set to CW, therefore we add 1 step to step count (positive values = number of steps in CW direction from initial postion)
585  }
586  else
587  {
588  pointer->stepCnt-=pointer->dropinStepSize; //DIR is set to CCW, therefore we subtract 1 step from step count (negative values = number of steps in CCW direction from initial postion)
589  }
590  }
591 }
592 
594 {
595 
596  int32_t stepsMoved;
597  int32_t stepCntTemp;
598  float error;
599  float output;
600  sei();
601 
603  stepsMoved = pointer->driver.getPosition();
604  if(pointer->mode == DROPIN)
605  {
606  cli();
607  stepCntTemp = pointer->stepCnt;
608  sei();
609 
611 
612  if(!pointer->pidDisabled)
613  {
614  error = (stepCntTemp - (int32_t)(pointer->encoder.angleMoved * ENCODERDATATOSTEP))/16;
616  pointer->pid(error);
617  }
618  return;
619  }
620  else if(pointer->mode == CLOSEDLOOP)
621  {
622  if(!pointer->pidDisabled)
623  {
626  {
629  }
630 
632  }
633  }
634 }
635 
636 void uStepperS::setControlThreshold(float threshold)
637 {
638  this->controlThreshold = threshold;
639 }
641 {
642  cli();
643  this->pidDisabled = 0;
644  sei();
645 }
646 
648 {
649  cli();
650  this->pidDisabled = 1;
651  sei();
652 }
653 
655 {
656  this->enablePid();
657 }
658 
660 {
661  this->disablePid();
662 }
663 
664 float uStepperS::moveToEnd(bool dir, float rpm, int8_t threshold)
665 {
666  // Lowest reliable speed for stallguard
667  if (rpm < 10.0)
668  rpm = 10.0;
669 
670  if(dir == CW)
671  this->setRPM(abs(rpm));
672  else
673  this->setRPM(-abs(rpm));
674 
675  delay(100);
676 
677  this->isStalled();
678  // Enable stallguard to detect hardware stop (use driver directly, as to not override user stall settings)
679  pointer->driver.enableStallguard( threshold, true, rpm );
680 
681  float length = this->encoder.getAngleMoved();
682 
683  while( !this->isStalled() ){}
684  this->stop();
685  pointer->driver.clearStall();
686 
687  // Return to normal operation
689 
690  length -= this->encoder.getAngleMoved();
691  delay(1000);
692  return abs(length);
693 }
694 
696 {
697  return this->currentPidError;
698 }
699 
700 float uStepperS::pid(float error)
701 {
702  float u;
703  float limit = abs(this->currentPidSpeed) + 10000.0;
704  static float integral;
705  static bool integralReset = 0;
706  static float errorOld, differential = 0.0;
707 
708  this->currentPidError = error;
709 
710  u = error*this->pTerm;
711 
712  if(u > 0.0)
713  {
714  if(u > limit)
715  {
716  u = limit;
717  }
718  }
719  else if(u < 0.0)
720  {
721  if(u < -limit)
722  {
723  u = -limit;
724  }
725  }
726 
727  integral += error*this->iTerm;
728 
729  if(integral > 200000.0)
730  {
731  integral = 200000.0;
732  }
733  else if(integral < -200000.0)
734  {
735  integral = -200000.0;
736  }
737 
738  if(error > -10 && error < 10)
739  {
740  if(!integralReset)
741  {
742  integralReset = 1;
743  integral = 0;
744  }
745  }
746  else
747  {
748  integralReset = 0;
749  }
750 
751  u += integral;
752 
753  differential *= 0.9;
754  differential += 0.1*((error - errorOld)*this->dTerm);
755 
756  errorOld = error;
757 
758  u += differential;
759 
760  u *= this->stepsPerSecondToRPM * 16.0;
761  this->setRPM(u);
762  this->driver.setDeceleration( 0xFFFE );
763  this->driver.setAcceleration( 0xFFFE );
764 }
765 
767 {
768  this->pTerm = P;
769 }
770 
772 {
773  this->iTerm = I * ENCODERINTPERIOD;
774 }
775 
777 {
778  this->dTerm = D * ENCODERINTFREQ;
779 }
780 
781 void uStepperS::invertDropinDir(bool invert)
782 {
783  this->invertPidDropinDirection = invert;
784 }
785 
786 void uStepperS::parseCommand(String *cmd)
787 {
788  uint8_t i = 0;
789  String value;
790 
791  if(cmd->charAt(2) == ';')
792  {
793  Serial.println("COMMAND NOT ACCEPTED");
794  return;
795  }
796 
797  value.remove(0);
798  /****************** SET P Parameter ***************************
799  * *
800  * *
801  **************************************************************/
802  if(cmd->substring(0,2) == String("P="))
803  {
804  for(i = 2;;i++)
805  {
806  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
807  {
808  value.concat(cmd->charAt(i));
809  }
810  else if(cmd->charAt(i) == '.')
811  {
812  value.concat(cmd->charAt(i));
813  i++;
814  break;
815  }
816  else if(cmd->charAt(i) == ';')
817  {
818  break;
819  }
820  else
821  {
822  Serial.println("COMMAND NOT ACCEPTED");
823  return;
824  }
825  }
826 
827  for(;;i++)
828  {
829  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
830  {
831  value.concat(cmd->charAt(i));
832  }
833  else if(cmd->charAt(i) == ';')
834  {
835  Serial.print("COMMAND ACCEPTED. P = ");
836  Serial.println(value.toFloat(),4);
837  this->dropinSettings.P.f = value.toFloat();
838  this->saveDropinSettings();
839  this->setProportional(value.toFloat());
840  return;
841  }
842  else
843  {
844  Serial.println("COMMAND NOT ACCEPTED");
845  return;
846  }
847  }
848  }
849 
850 /****************** SET I Parameter ***************************
851  * *
852  * *
853  **************************************************************/
854  else if(cmd->substring(0,2) == String("I="))
855  {
856  for(i = 2;;i++)
857  {
858  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
859  {
860  value.concat(cmd->charAt(i));
861  }
862  else if(cmd->charAt(i) == '.')
863  {
864  value.concat(cmd->charAt(i));
865  i++;
866  break;
867  }
868  else if(cmd->charAt(i) == ';')
869  {
870  break;
871  }
872  else
873  {
874  Serial.println("COMMAND NOT ACCEPTED");
875  return;
876  }
877  }
878 
879  for(;;i++)
880  {
881  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
882  {
883  value.concat(cmd->charAt(i));
884  }
885  else if(cmd->charAt(i) == ';')
886  {
887  Serial.print("COMMAND ACCEPTED. I = ");
888  Serial.println(value.toFloat(),4);
889  this->dropinSettings.I.f = value.toFloat();
890  this->saveDropinSettings();
891  this->setIntegral(value.toFloat());
892  return;
893  }
894  else
895  {
896  Serial.println("COMMAND NOT ACCEPTED");
897  return;
898  }
899  }
900  }
901 
902 /****************** SET D Parameter ***************************
903  * *
904  * *
905  **************************************************************/
906  else if(cmd->substring(0,2) == String("D="))
907  {
908  for(i = 2;;i++)
909  {
910  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
911  {
912  value.concat(cmd->charAt(i));
913  }
914  else if(cmd->charAt(i) == '.')
915  {
916  value.concat(cmd->charAt(i));
917  i++;
918  break;
919  }
920  else if(cmd->charAt(i) == ';')
921  {
922  break;
923  }
924  else
925  {
926  Serial.println("COMMAND NOT ACCEPTED");
927  return;
928  }
929  }
930 
931  for(;;i++)
932  {
933  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
934  {
935  value.concat(cmd->charAt(i));
936  }
937  else if(cmd->charAt(i) == ';')
938  {
939  Serial.print("COMMAND ACCEPTED. D = ");
940  Serial.println(value.toFloat(),4);
941  this->dropinSettings.D.f = value.toFloat();
942  this->saveDropinSettings();
943  this->setDifferential(value.toFloat());
944  return;
945  }
946  else
947  {
948  Serial.println("COMMAND NOT ACCEPTED");
949  return;
950  }
951  }
952  }
953 
954 /****************** invert Direction ***************************
955  * *
956  * *
957  **************************************************************/
958  else if(cmd->substring(0,6) == String("invert"))
959  {
960  if(cmd->charAt(6) != ';')
961  {
962  Serial.println("COMMAND NOT ACCEPTED");
963  return;
964  }
965  if(this->invertPidDropinDirection)
966  {
967  Serial.println(F("Direction normal!"));
968  this->dropinSettings.invert = 0;
969  this->saveDropinSettings();
970  this->invertDropinDir(0);
971  return;
972  }
973  else
974  {
975  Serial.println(F("Direction inverted!"));
976  this->dropinSettings.invert = 1;
977  this->saveDropinSettings();
978  this->invertDropinDir(1);
979  return;
980  }
981  }
982 
983  /****************** get Current Pid Error ********************
984  * *
985  * *
986  **************************************************************/
987  else if(cmd->substring(0,5) == String("error"))
988  {
989  if(cmd->charAt(5) != ';')
990  {
991  Serial.println("COMMAND NOT ACCEPTED");
992  return;
993  }
994  Serial.print(F("Current Error: "));
995  Serial.print(this->getPidError());
996  Serial.println(F(" Steps"));
997  }
998 
999  /****************** Get run/hold current settings ************
1000  * *
1001  * *
1002  **************************************************************/
1003  else if(cmd->substring(0,7) == String("current"))
1004  {
1005  if(cmd->charAt(7) != ';')
1006  {
1007  Serial.println("COMMAND NOT ACCEPTED");
1008  return;
1009  }
1010  Serial.print(F("Run Current: "));
1011  Serial.print(ceil(((float)this->driver.current)/0.31));
1012  Serial.println(F(" %"));
1013  Serial.print(F("Hold Current: "));
1014  Serial.print(ceil(((float)this->driver.holdCurrent)/0.31));
1015  Serial.println(F(" %"));
1016  }
1017 
1018  /****************** Get PID Parameters ***********************
1019  * *
1020  * *
1021  **************************************************************/
1022  else if(cmd->substring(0,10) == String("parameters"))
1023  {
1024  if(cmd->charAt(10) != ';')
1025  {
1026  Serial.println("COMMAND NOT ACCEPTED");
1027  return;
1028  }
1029  Serial.print(F("P: "));
1030  Serial.print(this->dropinSettings.P.f,4);
1031  Serial.print(F(", "));
1032  Serial.print(F("I: "));
1033  Serial.print(this->dropinSettings.I.f,4);
1034  Serial.print(F(", "));
1035  Serial.print(F("D: "));
1036  Serial.println(this->dropinSettings.D.f,4);
1037  }
1038 
1039  /****************** Help menu ********************************
1040  * *
1041  * *
1042  **************************************************************/
1043  else if(cmd->substring(0,4) == String("help"))
1044  {
1045  if(cmd->charAt(4) != ';')
1046  {
1047  Serial.println("COMMAND NOT ACCEPTED");
1048  return;
1049  }
1050  this->dropinPrintHelp();
1051  }
1052 
1053 /****************** SET run current ***************************
1054  * *
1055  * *
1056  **************************************************************/
1057  else if(cmd->substring(0,11) == String("runCurrent="))
1058  {
1059  for(i = 11;;i++)
1060  {
1061  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
1062  {
1063  value.concat(cmd->charAt(i));
1064  }
1065  else if(cmd->charAt(i) == '.')
1066  {
1067  value.concat(cmd->charAt(i));
1068  i++;
1069  break;
1070  }
1071  else if(cmd->charAt(i) == ';')
1072  {
1073  break;
1074  }
1075  else
1076  {
1077  Serial.println("COMMAND NOT ACCEPTED");
1078  return;
1079  }
1080  }
1081 
1082  for(;;i++)
1083  {
1084  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
1085  {
1086  value.concat(cmd->charAt(i));
1087  }
1088  else if(cmd->charAt(i) == ';')
1089  {
1090  if(value.toFloat() >= 0.0 && value.toFloat() <= 100.0)
1091  {
1092  i = (uint8_t)value.toFloat();
1093  break;
1094  }
1095  else
1096  {
1097  Serial.println("COMMAND NOT ACCEPTED");
1098  return;
1099  }
1100  }
1101  else
1102  {
1103  Serial.println("COMMAND NOT ACCEPTED");
1104  return;
1105  }
1106  }
1107 
1108  Serial.print("COMMAND ACCEPTED. runCurrent = ");
1109  Serial.print(i);
1110  Serial.println(F(" %"));
1111  this->dropinSettings.runCurrent = i;
1112  this->saveDropinSettings();
1113  this->setCurrent(i);
1114  }
1115 
1116  /****************** SET run current ***************************
1117  * *
1118  * *
1119  **************************************************************/
1120  else if(cmd->substring(0,12) == String("holdCurrent="))
1121  {
1122  for(i = 12;;i++)
1123  {
1124  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
1125  {
1126  value.concat(cmd->charAt(i));
1127  }
1128  else if(cmd->charAt(i) == '.')
1129  {
1130  value.concat(cmd->charAt(i));
1131  i++;
1132  break;
1133  }
1134  else if(cmd->charAt(i) == ';')
1135  {
1136  break;
1137  }
1138  else
1139  {
1140  Serial.println("COMMAND NOT ACCEPTED");
1141  return;
1142  }
1143  }
1144 
1145  for(;;i++)
1146  {
1147  if(cmd->charAt(i) >= '0' && cmd->charAt(i) <= '9')
1148  {
1149  value.concat(cmd->charAt(i));
1150  }
1151  else if(cmd->charAt(i) == ';')
1152  {
1153  if(value.toFloat() >= 0.0 && value.toFloat() <= 100.0)
1154  {
1155  i = (uint8_t)value.toFloat();
1156  break;
1157  }
1158  else
1159  {
1160  Serial.println("COMMAND NOT ACCEPTED");
1161  return;
1162  }
1163  }
1164  else
1165  {
1166  Serial.println("COMMAND NOT ACCEPTED");
1167  return;
1168  }
1169  }
1170 
1171  Serial.print("COMMAND ACCEPTED. holdCurrent = ");
1172  Serial.print(i);
1173  Serial.println(F(" %"));
1174  this->dropinSettings.holdCurrent = i;
1175  this->saveDropinSettings();
1176  this->setHoldCurrent(i);
1177  }
1178 
1179  /****************** DEFAULT (Reject!) ************************
1180  * *
1181  * *
1182  **************************************************************/
1183  else
1184  {
1185  Serial.println("COMMAND NOT ACCEPTED");
1186  return;
1187  }
1188 
1189 }
1190 
1192 {
1193  static String stringInput;
1194  static uint32_t t = millis();
1195 
1196  while(1)
1197  {
1198  while(!Serial.available())
1199  {
1200  delay(1);
1201  if((millis() - t) >= 500)
1202  {
1203  stringInput.remove(0);
1204  t = millis();
1205  }
1206  }
1207  t = millis();
1208  stringInput += (char)Serial.read();
1209  if(stringInput.lastIndexOf(';') > -1)
1210  {
1211  this->parseCommand(&stringInput);
1212  stringInput.remove(0);
1213  }
1214  }
1215 }
1216 
1218 {
1219  Serial.println(F("uStepper S Dropin !"));
1220  Serial.println(F(""));
1221  Serial.println(F("Usage:"));
1222  Serial.println(F("Show this command list: 'help;'"));
1223  Serial.println(F("Get PID Parameters: 'parameters;'"));
1224  Serial.println(F("Set Proportional constant: 'P=10.002;'"));
1225  Serial.println(F("Set Integral constant: 'I=10.002;'"));
1226  Serial.println(F("Set Differential constant: 'D=10.002;'"));
1227  Serial.println(F("Invert Direction: 'invert;'"));
1228  Serial.println(F("Get Current PID Error: 'error;'"));
1229  Serial.println(F("Get Run/Hold Current Settings: 'current;'"));
1230  Serial.println(F("Set Run Current (percent): 'runCurrent=50.0;'"));
1231  Serial.println(F("Set Hold Current (percent): 'holdCurrent=50.0;'"));
1232  Serial.println(F(""));
1233  Serial.println(F(""));
1234 }
1235 
1237 {
1238  dropinCliSettings_t tempSettings;
1239 
1240  EEPROM.get(0,tempSettings);
1241 
1242  if(this->dropinSettingsCalcChecksum(&tempSettings) != tempSettings.checksum)
1243  {
1244  return 0;
1245  }
1246 
1247  this->dropinSettings = tempSettings;
1248  this->setProportional(this->dropinSettings.P.f);
1249  this->setIntegral(this->dropinSettings.I.f);
1250  this->setDifferential(this->dropinSettings.D.f);
1251  this->invertDropinDir((bool)this->dropinSettings.invert);
1252  this->setCurrent(this->dropinSettings.runCurrent);
1254  return 1;
1255 }
1256 
1258 {
1260 
1261  EEPROM.put(0,this->dropinSettings);
1262 }
1263 
1265 {
1266  uint8_t i;
1267  uint8_t checksum = 0xAA;
1268  uint8_t *p = (uint8_t*)settings;
1269 
1270  for(i=0; i < 15; i++)
1271  {
1272  checksum ^= *p++;
1273  }
1274 
1275  return checksum;
1276 }
XTARGET
#define XTARGET
Definition: uStepperDriver.h:67
uStepperS::externalStepInputFilter
volatile posFilter_t externalStepInputFilter
Definition: uStepperS.h:744
uStepperS
Prototype of class for accessing all features of the uStepper S in a single object.
Definition: uStepperS.h:279
uStepperDriver::init
void init(uStepperS *_pointer)
Initiation of the motor driver.
Definition: uStepperDriver.cpp:71
uStepperS::dropinStepSize
uint16_t dropinStepSize
Definition: uStepperS.h:737
uStepperS::stepTime
float stepTime
Definition: uStepperS.h:714
dropinCliSettings_t::P
floatBytes_t P
Definition: uStepperS.h:188
uStepperDriver::disableStallguard
void disableStallguard(void)
Definition: uStepperDriver.cpp:399
uStepperS::velToRpm
float velToRpm
Definition: uStepperS.h:716
uStepperS::moveSteps
void moveSteps(int32_t steps)
Make the motor perform a predefined number of steps.
Definition: uStepperS.cpp:270
uStepperS::getMotorState
bool getMotorState(uint8_t statusType=POSITION_REACHED)
Get the current motor driver state.
Definition: uStepperS.cpp:84
uStepperS::stallEnabled
bool stallEnabled
Definition: uStepperS.h:774
uStepperDriver::setAcceleration
void setAcceleration(uint32_t acceleration)
Set motor acceleration.
Definition: uStepperDriver.cpp:120
uStepperDriver::readRegister
int32_t readRegister(uint8_t address)
Reads a register from the motor driver.
Definition: uStepperDriver.cpp:316
uStepperS::setBrakeMode
void setBrakeMode(uint8_t mode, float brakeCurrent=25.0)
Definition: uStepperS.cpp:362
uStepperS.h
uStepperDriver::readMotorStatus
void readMotorStatus(void)
Definition: uStepperDriver.cpp:102
PULSEFILTERKI
#define PULSEFILTERKI
Definition: uStepperS.h:245
uStepperEncoder::Beta
volatile uint8_t Beta
Definition: uStepperEncoder.h:230
uStepperS::enableStallguard
void enableStallguard(int8_t threshold=4, bool stopOnStall=false, float rpm=10.0)
Enable TMC5130 StallGuard.
Definition: uStepperS.cpp:320
uStepperEncoder::angleMoved
volatile int32_t angleMoved
Definition: uStepperEncoder.h:213
posFilter_t::velIntegrator
float velIntegrator
Definition: uStepperS.h:206
uStepperS::dTerm
float dTerm
Definition: uStepperS.h:754
uStepperDriver::getVelocity
int32_t getVelocity(void)
Returns the current speed of the motor driver.
Definition: uStepperDriver.cpp:236
uStepperEncoder::getAngleMoved
float getAngleMoved(bool filtered=true)
Returns the angle moved from reference position in degrees.
Definition: uStepperEncoder.cpp:184
uStepperS::getDriverRPM
float getDriverRPM(void)
Get the RPM from driver.
Definition: uStepperS.cpp:94
uStepperS::rpmToVelocity
float rpmToVelocity
Definition: uStepperS.h:731
dropinCliSettings_t
Struct to store dropin settings.
Definition: uStepperS.h:187
posFilter_t::velEst
float velEst
Definition: uStepperS.h:207
pointer
uStepperS * pointer
Definition: uStepperS.cpp:34
uStepperDriver::setVelocity
void setVelocity(uint32_t velocity)
Set motor velocity.
Definition: uStepperDriver.cpp:108
uStepperS::setSPIMode
void setSPIMode(uint8_t mode)
Definition: uStepperS.cpp:400
uStepperEncoder::captureAngle
uint16_t captureAngle(void)
Capture the current shaft angle.
Definition: uStepperEncoder.cpp:117
ACCELERATIONCONVERSION
#define ACCELERATIONCONVERSION
Definition: uStepperDriver.h:142
uStepperS::disableStallguard
void disableStallguard(void)
Disables the builtin stallguard offered from TMC5130, and reenables StealthChop.
Definition: uStepperS.cpp:331
CW
#define CW
Definition: uStepperS.h:160
dropinCliSettings_t::D
floatBytes_t D
Definition: uStepperS.h:190
uStepperS::runContinous
void runContinous(bool dir)
Make the motor rotate continuously.
Definition: uStepperS.cpp:487
uStepperS::disablePid
void disablePid(void)
This method disables the PID until calling enablePid.
Definition: uStepperS.cpp:647
SCK1
#define SCK1
Definition: uStepperS.h:228
uStepperS::fullSteps
uint16_t fullSteps
Definition: uStepperS.h:735
uStepperDriver::clearStall
void clearStall(void)
Definition: uStepperDriver.cpp:412
uStepperS::pTerm
float pTerm
Definition: uStepperS.h:750
uStepperS::maxAcceleration
float maxAcceleration
Definition: uStepperS.h:728
uStepperS::isStalled
bool isStalled(void)
This method returns a bool variable indicating wether the motor is stalled or not....
Definition: uStepperS.cpp:343
uStepperS::stepsPerSecondToRPM
float stepsPerSecondToRPM
Definition: uStepperS.h:741
FREEWHEELBRAKE
#define FREEWHEELBRAKE
Definition: uStepperS.h:156
uStepperS::dropinCli
void dropinCli()
This method is used to tune Drop-in parameters. After tuning uStepper S, the parameters are saved in ...
Definition: uStepperS.cpp:1191
uStepperEncoder::encoderFilter
volatile posFilter_t encoderFilter
Definition: uStepperEncoder.h:227
uStepperS::stepCnt
int32_t stepCnt
Definition: uStepperS.h:739
uStepperS::controlThreshold
volatile float controlThreshold
Definition: uStepperS.h:758
uStepperS::stop
void stop(bool mode=HARD)
Stop the motor.
Definition: uStepperS.cpp:505
uStepperS::encoder
uStepperEncoder encoder
Definition: uStepperS.h:291
RAMP_STAT
#define RAMP_STAT
Definition: uStepperDriver.h:71
uStepperDriver::updateCurrent
void updateCurrent(void)
Writes the current setting registers of the motor driver
Definition: uStepperDriver.cpp:156
uStepperDriver::current
uint8_t current
Definition: uStepperDriver.h:320
uStepperS::filterSpeedPos
void filterSpeedPos(posFilter_t *filter, int32_t steps)
Definition: uStepperS.cpp:522
uStepperS::getPidError
float getPidError(void)
This method returns the current PID error.
Definition: uStepperS.cpp:695
dropinCliSettings_t::checksum
uint8_t checksum
Definition: uStepperS.h:194
SD_MODE
#define SD_MODE
Definition: uStepperS.h:219
ENCODERDATATOSTEP
#define ENCODERDATATOSTEP
Definition: uStepperEncoder.h:41
uStepperS::setRPM
void setRPM(float rpm)
Set the velocity in rpm.
Definition: uStepperS.cpp:383
uStepperS::disableClosedLoop
void disableClosedLoop(void)
This method disables the closed loop mode until calling enableClosedLoop.
Definition: uStepperS.cpp:659
uStepperS::microSteps
uint16_t microSteps
Definition: uStepperS.h:734
uStepperS::iTerm
float iTerm
Definition: uStepperS.h:752
uStepperS::pidDisabled
volatile bool pidDisabled
Definition: uStepperS.h:756
uStepperS::parseCommand
void parseCommand(String *cmd)
This method is used for the dropinCli to take in user commands.
Definition: uStepperS.cpp:786
COOLBRAKE
#define COOLBRAKE
Definition: uStepperS.h:157
floatBytes_t::f
float f
Definition: uStepperS.h:174
uStepperS::moveToEnd
float moveToEnd(bool dir, float rpm=40.0, int8_t threshold=4)
Moves the motor to its physical limit, without limit switch.
Definition: uStepperS.cpp:664
uStepperS::setIntegral
void setIntegral(float I)
This method is used to change the PID integral parameter I.
Definition: uStepperS.cpp:771
uStepperS::RPMToStepsPerSecond
float RPMToStepsPerSecond
Definition: uStepperS.h:742
uStepperS::clearStall
void clearStall(void)
Clear the stallguard, reenabling the motor to return to its previous operation.
Definition: uStepperS.cpp:338
dropinCliSettings_t::invert
uint8_t invert
Definition: uStepperS.h:191
PULSEFILTERKP
#define PULSEFILTERKP
Definition: uStepperS.h:244
MOSI_ENC
#define MOSI_ENC
Definition: uStepperS.h:226
PWM_FREQ
#define PWM_FREQ(n)
Definition: uStepperDriver.h:79
uStepperS::init
void init(void)
Internal function to prepare the uStepperS in the constructor.
Definition: uStepperS.cpp:59
uStepperS::loadDropinSettings
bool loadDropinSettings(void)
Definition: uStepperS.cpp:1236
uStepperDriver::setPosition
void setPosition(int32_t position)
Set the motor position.
Definition: uStepperDriver.cpp:161
uStepperS::setDifferential
void setDifferential(float D)
This method is used to change the PID differential parameter D.
Definition: uStepperS.cpp:776
interrupt1
void interrupt1(void)
Used by dropin feature to take in enable signal.
Definition: uStepperS.cpp:546
dropinCliSettings_t::I
floatBytes_t I
Definition: uStepperS.h:189
posFilter_t::posError
float posError
Definition: uStepperS.h:204
uStepperS::setMaxVelocity
void setMaxVelocity(float velocity)
Set the maximum velocity of the stepper motor.
Definition: uStepperS.cpp:426
PWMCONF
#define PWMCONF
Definition: uStepperDriver.h:75
uStepperS::dropinSettingsCalcChecksum
uint8_t dropinSettingsCalcChecksum(dropinCliSettings_t *settings)
Definition: uStepperS.cpp:1264
uStepperS::enableClosedLoop
void enableClosedLoop(void)
This method reenables the closed loop mode after being disabled.
Definition: uStepperS.cpp:654
uStepperS::setup
void setup(uint8_t mode=NORMAL, uint16_t stepsPerRevolution=200, float pTerm=10.0, float iTerm=0.0, float dTerm=0.0, uint16_t dropinStepSize=16, bool setHome=true, uint8_t invert=0, uint8_t runCurrent=50, uint8_t holdCurrent=30)
Initializes the different parts of the uStepper S object.
Definition: uStepperS.cpp:167
uStepperS::interrupt0
friend void interrupt0(void)
Used by dropin feature to take in step pulses.
Definition: uStepperS.cpp:558
dropinCliSettings_t::holdCurrent
uint8_t holdCurrent
Definition: uStepperS.h:192
uStepperS::pid
float pid(float error)
Definition: uStepperS.cpp:700
uStepperEncoder::init
void init(uStepperS *_pointer)
Initiation of the encoder.
Definition: uStepperEncoder.cpp:50
uStepperS::mode
volatile uint8_t mode
Definition: uStepperS.h:749
PWM_GRAD
#define PWM_GRAD(n)
Definition: uStepperDriver.h:80
uStepperDriver::getPosition
int32_t getPosition(void)
Returns the current position of the motor driver.
Definition: uStepperDriver.cpp:247
CS_ENCODER
#define CS_ENCODER
Definition: uStepperS.h:223
uStepperS::angleToStep
float angleToStep
Definition: uStepperS.h:732
uStepperS::stallStop
bool stallStop
Definition: uStepperS.h:771
uStepperS::maxVelocity
float maxVelocity
Definition: uStepperS.h:722
dropinCliSettings_t::runCurrent
uint8_t runCurrent
Definition: uStepperS.h:193
PWM_AMPL
#define PWM_AMPL(n)
Definition: uStepperDriver.h:81
XACTUAL
#define XACTUAL
Definition: uStepperDriver.h:54
uStepperS::saveDropinSettings
void saveDropinSettings(void)
Definition: uStepperS.cpp:1257
uStepperDriver::holdCurrent
uint8_t holdCurrent
Definition: uStepperDriver.h:321
uStepperDriver::enableStallguard
void enableStallguard(int8_t threshold, bool stopOnStall, float rpm)
Definition: uStepperDriver.cpp:362
ENCODERINTPERIOD
#define ENCODERINTPERIOD
Definition: uStepperS.h:243
uStepperS::setMaxAcceleration
void setMaxAcceleration(float acceleration)
Set the maximum acceleration of the stepper motor.
Definition: uStepperS.cpp:437
CS_DRIVER
#define CS_DRIVER
Definition: uStepperS.h:222
uStepperS::angleMoved
float angleMoved(void)
Get the angle moved from reference position in degrees.
Definition: uStepperS.cpp:500
uStepperS::driver
uStepperDriver driver
Definition: uStepperS.h:288
VELOCITYCONVERSION
#define VELOCITYCONVERSION
Definition: uStepperDriver.h:143
ENCODERINTFREQ
#define ENCODERINTFREQ
Definition: uStepperS.h:242
FREEWHEEL
#define FREEWHEEL(n)
Definition: uStepperDriver.h:77
uStepperS::invertDropinDir
void invertDropinDir(bool invert)
This method is used to invert the drop-in direction pin interpretation.
Definition: uStepperS.cpp:781
uStepperDriver::status
uint8_t status
Definition: uStepperDriver.h:313
uStepperS::stallThreshold
int8_t stallThreshold
Definition: uStepperS.h:768
uStepperS::rpmToVel
float rpmToVel
Definition: uStepperS.h:715
uStepperS::shaftDir
volatile bool shaftDir
Definition: uStepperS.h:777
uStepperS::currentPidSpeed
float currentPidSpeed
Definition: uStepperS.h:746
uStepperS::moveAngle
void moveAngle(float angle)
Makes the motor rotate a specific angle relative to the current position.
Definition: uStepperS.cpp:285
uStepperEncoder::setHome
void setHome(float initialAngle=0)
Define new reference(home) position.
Definition: uStepperEncoder.cpp:82
uStepperS::dropinSettings
dropinCliSettings_t dropinSettings
Definition: uStepperS.h:789
uStepperS::SPI
uint8_t SPI(uint8_t data)
Definition: uStepperS.cpp:415
DROPIN
#define DROPIN
Definition: uStepperS.h:232
posFilter_t
Struct for encoder velocity estimator.
Definition: uStepperS.h:203
uStepperDriver::setDirection
void setDirection(bool direction)
Definition: uStepperDriver.cpp:182
uStepperS::checkOrientation
void checkOrientation(float distance=10)
This method is used to check the orientation of the motor connector.
Definition: uStepperS.cpp:101
VELOCITY_MODE_POS
#define VELOCITY_MODE_POS
Definition: uStepperDriver.h:134
uStepperS::setHoldCurrent
void setHoldCurrent(double current)
Set motor hold current.
Definition: uStepperS.cpp:473
uStepperS::uStepperS
uStepperS()
Constructor of uStepper class.
Definition: uStepperS.cpp:36
uStepperS::moveToAngle
void moveToAngle(float angle)
Makes the motor rotate to a specific absolute angle.
Definition: uStepperS.cpp:302
uStepperS::dropinPrintHelp
void dropinPrintHelp()
This method is used to print the dropinCli menu explainer:
Definition: uStepperS.cpp:1217
uStepperS::setControlThreshold
void setControlThreshold(float threshold)
This method sets the control threshold for the closed loop position control in microsteps - i....
Definition: uStepperS.cpp:636
uStepperS::currentPidError
volatile float currentPidError
Definition: uStepperS.h:765
MOSI1
#define MOSI1
Definition: uStepperS.h:225
uStepperS::maxDeceleration
float maxDeceleration
Definition: uStepperS.h:729
uStepperS::setProportional
void setProportional(float P)
This method is used to change the PID proportional parameter P.
Definition: uStepperS.cpp:766
CLOCKFREQ
#define CLOCKFREQ
Definition: uStepperS.h:236
uStepperS::enablePid
void enablePid(void)
This method reenables the PID after being disabled.
Definition: uStepperS.cpp:640
uStepperS::invertPidDropinDirection
bool invertPidDropinDirection
Definition: uStepperS.h:730
uStepperDriver::setShaftDirection
void setShaftDirection(bool direction)
Set motor driver direction.
Definition: uStepperDriver.cpp:169
VACTUAL
#define VACTUAL
Definition: uStepperDriver.h:55
uStepperDriver::setDeceleration
void setDeceleration(uint32_t deceleration)
Set motor deceleration.
Definition: uStepperDriver.cpp:132
HARD
#define HARD
Definition: uStepperS.h:215
PWM_AUTOSCALE
#define PWM_AUTOSCALE(n)
Definition: uStepperDriver.h:78
CLOSEDLOOP
#define CLOSEDLOOP
Definition: uStepperS.h:233
DRV_ENN
#define DRV_ENN
Definition: uStepperS.h:218
uStepperS::setMaxDeceleration
void setMaxDeceleration(float deceleration)
Set the maximum deceleration of the stepper motor.
Definition: uStepperS.cpp:449
TIMER1_COMPA_vect
void TIMER1_COMPA_vect(void)
Definition: uStepperS.cpp:593
uStepperS::setCurrent
void setCurrent(double current)
Set motor output current.
Definition: uStepperS.cpp:460
uStepperDriver::setRampMode
void setRampMode(uint8_t mode)
Set motor driver to position mode or velocity mode.
Definition: uStepperDriver.cpp:192
uStepperDriver::xTarget
volatile int32_t xTarget
Definition: uStepperDriver.h:305
posFilter_t::posEst
float posEst
Definition: uStepperS.h:205
uStepperDriver::writeRegister
int32_t writeRegister(uint8_t address, uint32_t datagram)
Write a register of the motor driver.
Definition: uStepperDriver.cpp:284
interrupt0
void interrupt0(void)
Used by dropin feature to take in step pulses.
Definition: uStepperS.cpp:558