Testprogram for TMC2209-Library. Uses Speed-Control via VACTUAL instead of Step/Dir

Dependencies:   TMCStepper mRotaryEncoder-os

Revision:
5:7f250f463aa2
Parent:
4:12bfa2c1729f
Child:
6:6ad7bc10ac20
--- a/main.cpp	Thu Mar 18 20:48:31 2021 +0000
+++ b/main.cpp	Sun Mar 21 13:31:53 2021 +0000
@@ -12,12 +12,14 @@
 */
 
 
-DigitalOut ledDir(LED2);
+DigitalOut ledCW(LED1);  // Show totation clockwise
+DigitalOut ledCCW(LED2); // Show rotation counterclockwise
+
 //Virtual serial port over USB with 15200 baud 8N1
 static BufferedSerial host(USBTX, USBRX,115200);
 
 //mRotaryEncoder(PinName pinA, PinName pinB, PinName pinSW, PinMode pullMode=PullUp, int debounceTime_us=1000)
-mRotaryEncoder  wheel(p16, p17, p18,PullUp,1500);
+mRotaryEncoder  wheel(p16, p17, p18,PullUp,3000); // default 1500
 
 // hardware parameters:
 // MOTOR Steps per Revolution ( 1/8 Microsteps, 200Steps per Rev / 1.8 degrees per FullStep)
@@ -26,16 +28,18 @@
 #define GR 288
 
 #define DRIVER_ADDRESS 0b00 // TMC2209 Driver address according to MS1 and MS2
-#define R_SENSE 0.11f   // R-Sense in OHM.Match to your driver
+#define R_SENSE 0.11f   // R-Sense in OHM. Match to your driver
 #define MICROSTEPS 128  // # of microsteps
-#define RMSCURRENT 600  // RMS current of Stepper Coil in mA
+#define RMSCURRENT 800  // RMS current of Stepper Coil in mA
+#define MAXSPEED 5000   // Maximaum speed (5000 with RMS800 @12V/06Amax)
 
 // A TMCStepper-object with UART and given address and R-Sense
 //RX, TX, RS, Addr 
 TMC2209Stepper stepper(p14, p13, R_SENSE, DRIVER_ADDRESS);
 
-bool enc_pressed = false;      // Button of rotaryencoder was pressed
-bool enc_rotated = false;      // rotary encoder was totaded left or right
+volatile bool enc_pressed = false;      // Button of rotaryencoder was pressed
+volatile bool enc_rotated = false;      // rotary encoder was totaded left or right
+volatile bool enc_action  = false;      // any change happened
 int lastGet;
 int thisGet;
 
@@ -69,7 +73,7 @@
  {
     printf("\r\nConnected to mbed\r\n");
     
-    //Int-Handler for RotaryEncoder
+    //Intitiallize RotaryEncoder
     // call trigger_sw() when button of rotary-encoder is pressed
     wheel.attachSW(&trigger_sw);
     // call trigger_rot() when the shaft is rotaded left or right
@@ -77,20 +81,30 @@
     lastGet = 0;
     // set encrotated, so startup
     enc_rotated = true;
-    
+    enc_action = true;
+    ledCW = 1;
+    ledCCW = 1;
+        
+    // Initialize Stepper
+    printf("connecting to TMC-Module...\r\n");
     stepper.begin();                    // UART: Init SW UART (if selected) with default baudrate
+    printf("TMC-Version: %02X\r\n",stepper.version());
     stepper.toff(3);                    // Enables driver in software - 3, 5 ????
     stepper.rms_current(RMSCURRENT);    // Set motor RMS current in mA / min 500 for 24V/speed:3000
                                         // 1110, 800
+                                        // working: 800 12V/0,6Amax,  Speed up to 5200=4U/min
+                                        
     stepper.microsteps(MICROSTEPS);   // Set microsteps to 1:Fullstep ... 256: 1/256th
     stepper.en_spreadCycle(true);     // Toggle spreadCycle on TMC2208/2209/2224: default false, true: much faster!!!!
     stepper.pwm_autoscale(true);      // Needed for stealthChop
-    printf("TMC-Version: %02X\r\n",stepper.version());
     
-    bool shaft = false;  //direction CW or CCW
+    uint32_t status = stepper.DRV_STATUS();
+    printf("DRV_STATUS(): "); printBits(sizeof(status),&status);printf("\r\n");
+    
+    //bool shaft = false;  //direction CW or CCW
     
     while(1) {
-/*        
+/*  Spped-UP/Down-Cycles      
 //        printf("TSTEP(): %i\r\n", stepper.TSTEP());
         uint32_t status = stepper.DRV_STATUS();
         printf("DRV_STATUS(): "); printBits(sizeof(status),&status);printf("\r\n");
@@ -135,22 +149,51 @@
         printf("IFCNT(): %zu \r\n",stepper.IFCNT());
         printf("...\r\n");
 */
+////// Control motor-speed by rotary-encoder
+    
     // shaft has been rotated?
     if (enc_rotated) {
         enc_rotated = false;
+        enc_action = true;
         thisGet = wheel.Get();
+        if (thisGet*100 > MAXSPEED) { //on upper limit?
+            wheel.Set( MAXSPEED/100);
+            thisGet = wheel.Get();
+        }
+        if (thisGet*100 < MAXSPEED*(-1)) { //on lower limit?
+            wheel.Set( MAXSPEED*(-1)/100);
+            thisGet = wheel.Get();
+        } 
         stepper.VACTUAL(thisGet*100*MICROSTEPS);// Set Speed to value
         printf("actspeed: %i\r\n",thisGet*100);
-
+        
     }
     // Button pressed?
     if (enc_pressed) {
         enc_pressed = false;
+        enc_action = true;
         wheel.Set(0);
         thisGet = wheel.Get();
         stepper.VACTUAL(thisGet*100*MICROSTEPS);// Set Speed to value
         printf("actspeed: %i\r\n",thisGet*100);
 
     }        
+    // anything changed?
+    if (enc_action) {
+        enc_action = false;
+        // show direction of motor on leds
+        if (thisGet > 0) {
+            ledCW = 1;
+            ledCCW= 0;
+        }
+        if (thisGet < 0) {
+            ledCW = 0;
+            ledCCW= 1;
+        }
+        if (thisGet == 0) {
+            ledCW = 1;
+            ledCCW= 1;
+        }
+    }
    } // while 1
  }
\ No newline at end of file