What should voltage of output be with no stepper connected?

Hi,
i’m trying to get 36v4 working for the first time. i just received my 3rd 36v4 because i was afraid i might have burnt out the first two (17 stepper not moving or making any noise). Before i connect stepper i would like to make sure everything is ok. i put scope probes on AOUT1, AOUT2, BOUT1, BOUT2 (probe ground connected to power side GND of 36v4) and they all look the same, about about 0.5 volts and not changing (i assume this is not correct). So i assume if i connect stepper it will not move or make any noise.

What should i expect to see on scope?

i’m running modified version of BasicSteppingSPI shown below

measured:
IOREF: 3.2V
!SLEEP: 3.2V
VIN: 24.X V
V5(OUT): 5V
RESET: 0V

serial log of Teensy 4.0 looks like below
readStatus 0x0
readFaults 0x0
readStatus 0x0
readFaults 0x0
readStatus 0x0
readFaults 0x0
readStatus 0x0
readFaults 0x0
readStatus 0x0
readFaults 0x0

modified arduino code below:

// This example shows basic use of a Pololu High Power Stepper Motor Driver.
//
// It shows how to initialize the driver, configure various settings, and enable
// the driver.  It shows how to step the motor and switch directions using the
// driver's SPI interface through the library's step() and setDirection() member
// functions.
//
// Since SPI is used to trigger steps and set the direction, connecting the
// driver's STEP and DIR pins is optional for this example.  However, note that
// using SPI control adds some overhead compared to using the STEP and DIR pins.
// In addition, since the library caches SPI register values, SPI control is
// more likely to re-enable the driver with the wrong settings (e.g. current
// limit) after a power interruption, although using the verifySettings() and
// applySettings() functions appropriately can help prevent this.
//
// Before using this example, be sure to change the setCurrentMilliamps36v4 line
// to have an appropriate current limit for your system.  Also, see this
// library's documentation for information about how to connect the driver:
//   http://pololu.github.io/high-power-stepper-driver

#include <SPI.h>
#include <HighPowerStepperDriver.h>

//const uint8_t CSPin = 4;
const uint8_t CSPin = 10;

// This period is the length of the delay between steps, which controls the
// stepper motor's speed.  You can increase the delay to make the stepper motor
// go slower.  If you decrease the delay, the stepper motor will go faster, but
// there is a limit to how fast it can go before it starts missing steps.
const uint16_t StepPeriodUs = 2000;

HighPowerStepperDriver sd;
const int LeftStepperSleep = 8;
const int LeftStepperReset = 6;


void configure_stepper_driver(void)
{
  Serial.printf("configure_stepper_driver \n");

  
  pinMode(LeftStepperReset, OUTPUT);
  digitalWrite(LeftStepperReset, HIGH);   // 
  delayMicroseconds(1000);
  digitalWrite(LeftStepperReset, LOW);   // 
  delayMicroseconds(1000);

  
  // Give the driver some time to power up.
  delay(1);

  // Reset the driver to its default settings and clear latched status
  // conditions.
  sd.resetSettings();
  sd.clearStatus();

  // Select auto mixed decay.  TI's DRV8711 documentation recommends this mode
  // for most applications, and we find that it usually works well.
  sd.setDecayMode(HPSDDecayMode::AutoMixed);

  // Set the current limit. You should change the number here to an appropriate
  // value for your particular system.
  sd.setCurrentMilliamps36v4(1000);

  // Set the number of microsteps that correspond to one full step.
  sd.setStepMode(HPSDStepMode::MicroStep32);


  
}

void setup()
{
  Serial.printf("setup \n");

  SPI.begin();
  sd.setChipSelectPin(CSPin);


  pinMode(LeftStepperSleep, OUTPUT);
  digitalWrite(LeftStepperSleep, HIGH);   // 


  configure_stepper_driver();
#if 0
  pinMode(LeftStepperReset, OUTPUT);
  digitalWrite(LeftStepperReset, HIGH);   // 
  delayMicroseconds(1000);
  digitalWrite(LeftStepperReset, LOW);   // 
  delayMicroseconds(1000);

  
  // Give the driver some time to power up.
  delay(1);

  // Reset the driver to its default settings and clear latched status
  // conditions.
  sd.resetSettings();
  sd.clearStatus();

  // Select auto mixed decay.  TI's DRV8711 documentation recommends this mode
  // for most applications, and we find that it usually works well.
  sd.setDecayMode(HPSDDecayMode::AutoMixed);

  // Set the current limit. You should change the number here to an appropriate
  // value for your particular system.
  sd.setCurrentMilliamps36v4(1000);

  // Set the number of microsteps that correspond to one full step.
  sd.setStepMode(HPSDStepMode::MicroStep32);

#endif
  
  // Enable the motor outputs.
  sd.enableDriver();



//    digitalWrite(LeftStepperSleep, HIGH);   // 

}




void loop()
{
  int current_status;
  int current_faults;

current_status = sd.readStatus();
current_faults = sd.readFaults();
Serial.printf("readStatus 0x%x  \n",current_status);
Serial.printf("readFaults 0x%x  \n",current_faults);
//sd.clearFaults();
//sd.clearStatus();
if( (current_status != 0) || (current_faults != 0) )
{
  configure_stepper_driver();
  current_status = sd.readStatus();
  current_faults = sd.readFaults();
  Serial.printf("post readStatus 0x%x  \n",current_status);
  Serial.printf("post readFaults 0x%x  \n",current_faults);
}

  
  // Step in the default direction 1000 times.
if( (current_status == 0) && (current_faults == 0) )
{
  sd.setDirection(0);
  for(unsigned int x = 0; x < 1000; x++)
  {
    sd.step();
    delayMicroseconds(StepPeriodUs);
  }
}
  // Wait for 300 ms.
  delay(300);

  // Step in the other direction 1000 times.
if( (current_status == 0) && (current_faults == 0) )
{
  sd.setDirection(1);
  for(unsigned int x = 0; x < 1000; x++)
  {
    sd.step();
    delayMicroseconds(StepPeriodUs);
  }
}
else
{
  delay(1000);
}

  // Wait for 300 ms.
  delay(300);
}

seems DRV8711 register reads worked ok, but writes not working. First bit (read/write bit) not read correctly. Fixed by changing
SPISettings settings = SPISettings(500000, MSBFIRST, SPI_MODE0);
to
SPISettings settings = SPISettings(500000, MSBFIRST, SPI_MODE3);
in HighPowerStepperDriver.h

now both reads and writes working. and finally stepper motor is moving.

I’m running arduino on Teensy 4.0 board. SPI_MODE3 seems to be correct, not sure why others are not having more problems?

Hello,

I’m glad to hear your driver is working for you now. Thanks for letting us know what you found. It does seem strange that you had to change the SPI mode; we’ve tested the library quite a bit on standard Arduinos and I don’t think we’ve heard of anyone else having that issue, so I’m wondering if it’s something specific to the Teensy 4. If you have the opportunity to take oscilloscope captures of the SPI signals in both modes, we would be interested in seeing them.

Kevin

sorry, i had my scope connected to spi lines but did not save any images. and now it would be difficult to reconnect test wires for scope connection :frowning: If i remember correctly i thought the problem was clock line was low before chip select is asserted and first edge of clock line after chip select is asserted goes from low to high. changing to SPI_MODE3 changed this so that clock line is generally high and first transition after chip select is asserted goes from high to low and then first bit is read correctly. if i remember correctly.