Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Stallguard with AccelStepper Library #69

Open
martinmatias opened this issue Feb 5, 2019 · 11 comments
Open

Stallguard with AccelStepper Library #69

martinmatias opened this issue Feb 5, 2019 · 11 comments

Comments

@martinmatias
Copy link

martinmatias commented Feb 5, 2019

Hi, I want to use Stallguard and a Library to run the stepper such as Accelstepper Library. I've combined Stallguard example and Accelstepper example. Stepper is running but output is:

0 0 55
0 0 55
0 0 55

meaning that driver.DRV_STATUS(); return same value al the time.
I've tried to put stepper.run(); inside ISR code, inside loop(). Also tried with conditional into ISR and into loop code, but still not load detected (stepper motor running withput problems).

Any ideas? Bellow the code used
Regards
Martin

/**
 * Author Teemu Mäntykallio
 * Initializes the library and turns the motor in alternating directions.
*/

#include <TMC2130Stepper.h>
#include <AccelStepper.h>
#include <TMC2130Stepper_REGDEFS.h>

#define EN_PIN    6  // Nano v3:  16 Mega:  38  //enable (CFG6)
#define DIR_PIN   4  //           19        55  //direction
#define STEP_PIN  5  //           18        54  //step
#define CS_PIN    10  //           17        64  //chip select


byte MOSI_PIN = 11; //SDI/MOSI (ICSP: 4, Uno: 11, Mega: 51)
byte MISO_PIN = 12; //SDO/MISO (ICSP: 1, Uno: 12, Mega: 50)
byte SCK_PIN  = 13; //CLK/SCK  (ICSP: 3, Uno: 13, Mega: 52)

#define MAX_SPEED  40 // In timer value
#define MIN_SPEED  1000

#define STALL_VALUE 0 // [-64..63]


constexpr uint32_t steps_per_mm = 80;
int dir = -1  ;

//TMC2130Stepper driver = TMC2130Stepper(EN_PIN, DIR_PIN, STEP_PIN, CS_PIN);
TMC2130Stepper driver = TMC2130Stepper(EN_PIN, DIR_PIN, STEP_PIN, CS_PIN, MOSI_PIN, MISO_PIN, SCK_PIN);

AccelStepper stepper = AccelStepper(stepper.DRIVER, STEP_PIN, DIR_PIN);

bool vsense;

uint16_t rms_current(uint8_t CS, float Rsense = 0.11) {
  return (float)(CS+1)/32.0 * (vsense?0.180:0.325)/(Rsense+0.02) / 1.41421 * 1000;
}

void setup() {
  {
    Serial.begin(250000); //init serial port and set baudrate
    while(!Serial); //wait for serial port to connect (needed for Leonardo only)
    Serial.println("\nStart...");
    pinMode(EN_PIN, OUTPUT);
    pinMode(DIR_PIN, OUTPUT);
    pinMode(STEP_PIN, OUTPUT);
    pinMode(CS_PIN, OUTPUT);
    digitalWrite(EN_PIN, HIGH); //deactivate driver (LOW active)
    digitalWrite(DIR_PIN, LOW); //LOW or HIGH
    digitalWrite(STEP_PIN, LOW);
    digitalWrite(CS_PIN, HIGH);
    SPI.begin();
    pinMode(MISO_PIN, INPUT_PULLUP);
  }
    
  {
    driver.push();
    driver.toff(3);
    driver.tbl(1);
    driver.hysteresis_start(4);
    driver.hysteresis_end(-2);
    driver.rms_current(600); // mA
    driver.microsteps(16);
    driver.diag1_stall(1);
    driver.diag1_active_high(1);
    driver.coolstep_min_speed(0xFFFFF); // 20bit max
    driver.THIGH(0);
    driver.semin(5);
    driver.semax(2);
    driver.sedn(0b01);
    driver.sg_stall_value(STALL_VALUE);
    driver.stealthChop(1);
  }

   
   {
    stepper.setMaxSpeed(50*steps_per_mm); // 100mm/s @ 80 steps/mm
    stepper.setAcceleration(1000*steps_per_mm); // 2000mm/s^2
    stepper.setEnablePin(EN_PIN);
    stepper.setPinsInverted(false, false, true);
    stepper.enableOutputs();
 
   }

  {
    cli();//stop interrupts
    TCCR1A = 0;// set entire TCCR1A register to 0
    TCCR1B = 0;// same for TCCR1B
    TCNT1  = 0;//initialize counter value to 0
    OCR1A = 512;// = (16*10^6) / (1*1024) - 1 (must be <65536)
    // turn on CTC mode
    TCCR1B |= (1 << WGM12);
    // Set CS11 bits for 8 prescaler
    TCCR1B |= (1 << CS11);// | (1 << CS10);  
    // enable timer compare interrupt
    TIMSK1 |= (1 << OCIE1A);
    sei();//allow interrupts
  }


  digitalWrite(EN_PIN, LOW);
  vsense = driver.vsense();
}
ISR(TIMER1_COMPA_vect){

      if (stepper.distanceToGo() == 0) {
 //       stepper.disableOutputs();
        //delay(500);
        stepper.move(dir*1000*steps_per_mm); // Move 100mm

//        stepper.enableOutputs();
        //dir = dir*-1;
    }
  
    stepper.run();
  
}

void loop()
{
  static uint32_t last_time=0;
  uint32_t ms = millis();

  while(Serial.available() > 0) {
    int8_t read_byte = Serial.read();
    if (read_byte == '0')      { TIMSK1 &= ~(1 << OCIE1A); digitalWrite( EN_PIN, HIGH ); }
    else if (read_byte == '1') { TIMSK1 |=  (1 << OCIE1A); digitalWrite( EN_PIN,  LOW ); }
    else if (read_byte == '+') if (OCR1A > MAX_SPEED) OCR1A -= 20;
    else if (read_byte == '-') if (OCR1A < MIN_SPEED) OCR1A += 20;
  }
    
  if((ms-last_time) > 100) //run every 0.1s
  {
    last_time = ms;
    
    uint32_t drv_status = driver.DRV_STATUS();
    Serial.print("0 ");
    Serial.print((drv_status & SG_RESULT_bm)>>SG_RESULT_bp , DEC);
    Serial.print(" ");
    Serial.println(rms_current((drv_status & CS_ACTUAL_bm)>>CS_ACTUAL_bp), DEC);
  }
}
@danielawd
Copy link

I go the same output with accelstepper/stallguard!
0 0 55
0 0 55
0 0 55
Any solution?

@mightymietz
Copy link

Would be really interesting if someone could give a solution here. I have the same problem.

@teemuatlut
Copy link
Owner

Going by the code above, stallGuard doesn't work with stealthChop.
I'd also move the distance check out of ISR and remove the control characters for timer interval as you'd likely want that to be constant and let AccelStepper determine if a step needs to be taken or not.

@22chrs
Copy link

22chrs commented May 12, 2019

Would be really interesting if someone could give a solution here. I have the same problem.

Me too! I would really appreciate if someone found a solution. :) Trying too get this done on teensy 3.2 – so I also have to rewrite the interrupts.

@martinmatias
Copy link
Author

Hi guy, sorry for the delay. I've make my project work (curtain) checking distance using stallguard with stealthChop(0). After that I know the limits, I stop using stallguard and using stealthchop(1). The problem is if for some reason something block the curtain, the stepper will try to move the curtain all distance long making huge noise, but didnt happen yet.

@MilanVDB
Copy link

@martinmatias could you post the working code please. I tried to do what teematlut suggested put it doesnt complile

@Patrick-Yao-SRE
Copy link

@martinmatias Hello, I know this has been a while but is it possible for you to share with me the working code you have for the StallGuard?

@teemuatlut
Copy link
Owner

https://github.com/teemuatlut/TMCStepper

/**
 * Author Teemu Mäntykallio
 *
 * Plot TMC2130 or TMC2660 motor load using the stallGuard value.
 * You can finetune the reading by changing the STALL_VALUE.
 * This will let you control at which load the value will read 0
 * and the stall flag will be triggered. This will also set pin DIAG1 high.
 * A higher STALL_VALUE will make the reading less sensitive and
 * a lower STALL_VALUE will make it more sensitive.
 */
#include <TMCStepper.h>

#define STALL_VALUE      15 // [-64..63]

#define EN_PIN           62 // Enable
#define DIR_PIN          48 // Direction
#define STEP_PIN         46 // Step
#define CS_PIN           53 // Chip select
#define SW_MOSI          66 // Software Master Out Slave In (MOSI)
#define SW_MISO          44 // Software Master In Slave Out (MISO)
#define SW_SCK           64 // Software Slave Clock (SCK)

#define R_SENSE 0.11f // Match to your driver
                      // SilentStepStick series use 0.11
                      // UltiMachine Einsy and Archim2 boards use 0.2
                      // Panucatt BSD2660 uses 0.1
                      // Watterott TMC5160 uses 0.075

// Select your stepper driver type
TMC2130Stepper driver(CS_PIN, R_SENSE);                           // Hardware SPI

using namespace TMC2130_n;

#include <AccelStepper.h>
AccelStepper stepper = AccelStepper(stepper.DRIVER, STEP_PIN, DIR_PIN);

ISR(TIMER1_COMPA_vect){
  stepper.run();
}

void setup() {
  SPI.begin();
  Serial.begin(115200);         // Init serial port and set baudrate
  while(!Serial);               // Wait for serial port to connect
  Serial.println("\nStart...");

  pinMode(EN_PIN, OUTPUT);
  pinMode(STEP_PIN, OUTPUT);
  pinMode(CS_PIN, OUTPUT);
  pinMode(DIR_PIN, OUTPUT);
  pinMode(MISO, INPUT_PULLUP);
  digitalWrite(EN_PIN, LOW);

  driver.begin();
  driver.toff(3);
  driver.intpol(true);
  driver.blank_time(24);
  driver.rms_current(400); // mA
  driver.microsteps(4);
  driver.TCOOLTHRS(0xFFFFF); // 20bit max
  driver.THIGH(0);
  driver.semin(0);
  driver.semax(2);
  driver.sedn(0b01);
  driver.sgt(STALL_VALUE);

  // Set stepper interrupt @ 800Hz
  {
    cli();//stop interrupts
    TCCR1A = 0;// set entire TCCR1A register to 0
    TCCR1B = 0;// same for TCCR1B
    TCNT1  = 0;//initialize counter value to 0
    OCR1A = 20000;// = (16*10^6) / (1*1024) - 1 (must be <65536)
    // turn on CTC mode
    TCCR1B |= (1 << WGM12);
    // Set CS11 bits for 8 prescaler
    TCCR1B |= (1 << CS10);
    // enable timer compare interrupt
    TIMSK1 |= (1 << OCIE1A);
    sei();//allow interrupts
  }

  stepper.setMaxSpeed(800);
  stepper.setAcceleration(400);
  stepper.setEnablePin(EN_PIN);
  stepper.setPinsInverted(false, false, true);
  stepper.enableOutputs();
}

char buffer[128] = {0};

void loop() {
  static uint32_t last_time=0;
  uint32_t ms = millis();

  if((ms-last_time) > 100) { //run every 0.1s
    last_time = ms;

    DRV_STATUS_t drv_status{0};
    drv_status.sr = driver.DRV_STATUS();

    sprintf(buffer, "%5lu %5u %4u %u",
      stepper.distanceToGo(),
      static_cast<uint16_t>(stepper.speed()),
      drv_status.sg_result,
      driver.cs2rms(drv_status.cs_actual)
      );
    Serial.println(buffer);
  }

  if (stepper.distanceToGo() == 0) {
    stepper.disableOutputs();
    delay(1000);
    stepper.move(3000);
    stepper.enableOutputs();
  }
}

image

@Patrick-Yao-SRE
Copy link

Many thanks. I am suspecting the reason why my code and setup is not working because I am using Bigtreetech tmc2130. I am getting the silentstepstick version and try again.

@fatihelbl
Copy link

Hello, Thank you for your examples. It keeps me informed about TMCStepper. I tried the last example here. As seen in the graph, the speed first increases and then decreases. I want the engine speed to increase slowly and continue at full speed. How can I work on this issue?
thank you.

@maltuino
Copy link

maltuino commented Apr 28, 2022 via email

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

9 participants