Open-loop test with Arduino Mega 2560 and Trinamics TMC6200-BOB

Hi all,

I’m trying to pass the 3PWM open-loop test with the following setup:

  • MCU: Arduino Mega 2560
  • Driver: Trinamics TMC6200-BOB
  • Motor: iPower Motor GM3506

Unfortunately, I cannot manage to make it work. The Trinamics TMC6200-BOB has a fault detection feature that triggers as soon as I power my setup, disabling the power stage of the driver. I supply the motor with a lab power bench set on +12V, and no overcurrent is detected.

Is there something wrong with my setup? I’d be grateful for any help!

Hey,

I have TMC6200 and TMC6300, they are 6PWM logic and i had no success running them on 3PWM,
it seem that whenever i tried to save some PWM I/O with 3PWM i had the DIAG led turned on.

What you can do is hook up BOB to Motor without logic, and try spin BLDC motor, the diag should lit white.

Also you need DRV_EN to be high, if its driven too low it will produce fault and will trigger DIAG led on,
Although with SimpleFOC the driver enable is optional and so is for some of the IC’s, the TMC’s on high power chips require EN to be driven hight and mandatory.

Did you hook it up to SPI to read the registers of driver? This IC is some badass one allow to make very reliable designs with the SPI interface read out, it monitors almost all input pins:

0 UL
1 UH
2 VL
3 VH
4 WL
5 WH
6 DRV_EN
7 0
8 OTPW
9 OT136°C
10 OT143°C

Hi Karl, thank you very much for your help!

I also tried the 6PWM with no better luck. This time, the FAULT pin stays low but the motor doesn’t move and stays very stiff, and my power bench voltage drops and current limit triggers… I checked that the PWM pins I used were from the same timer for the Arduino Mega 2560:

U: pins 11 (high side) and 12 (low side) → timer1
V: pins 9 (high side) and 10 (low side) → timer2
W: pins 7 (high side) and 8 (low side) → timer4

For the DRV_EN pin, I just tied it to +Vio as I saw on the TMC6200 datasheet. Isn’t it equivalent to using the enable function with SimpleFOC?

I’ll try to check the registers with the 3PWM, but as my attempt with the 6PWM was unsuccessful, it tells me that maybe something else is happening here.

Here is my code, if someone wants to have a look:

// Open loop motor control example
#include <SimpleFOC.h>

// BLDC motor & driver instance
// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(11);
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver6PWM driver = BLDCDriver6PWM(11, 12, 9, 10, 7, 8);

// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }

int faultIn = 2; // FAULT output of driver connected to pin 2
int ledPin = 13;  // LED connected to digital pin 13
int faultState = 0; // variable to store the driver FAULT state

void setup() {

  pinMode(faultIn, INPUT);
  pinMode(ledPin, OUTPUT);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  driver.pwm_frequency = 20000;
  driver.dead_zone = 0.05;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);

  // limiting motor movements
  motor.phase_resistance = 12.5; // [Ohm]
  motor.current_limit = 2;   // [Amps] - if phase resistance defined
  motor.velocity_limit = 5; // [rad/s] cca 50rpm
 
  // open loop control config
  motor.controller = MotionControlType::velocity_openloop;

  // init motor hardware
  motor.init();

  // add target command T
  command.add('T', doTarget, "target velocity");

  Serial.begin(115200);
  Serial.println("Motor ready!");
  Serial.println("Set target velocity [rad/s]");
  _delay(1000);
}

void loop() {

  faultState = digitalRead(faultIn);

  if (faultState == HIGH)
    digitalWrite(ledPin, HIGH);
  else
    digitalWrite(ledPin, LOW);

  // open loop velocity movement
  // using motor.voltage_limit and motor.velocity_limit
  motor.move();

  // user communication
  command.run();
}

The disable() function depends on a hardware enable/disable function in the driver, and the enable pin being connected to the MCU and passed to the driver, for it to actually be able to physically disable the driver… otherwise, the disable() function just sets the PWM to zero, which normally will close all the high side FETs, open all the low side FETs, but leave everything else “on”, so to speak.

Hello,
Thanks, I see!
I tied pin 5 of the Arduino Mega to the DRV_EN pin of the TMC6200-BOB and declared it as the “enabled pin” in the BLDCDriver6PWM declaration, but nothing happened… Then I removed the jumper from pin 5 to DRV_EN and left it unconnected, and the motor started to move randomly (jitter), and the PSU voltage dropped from 12V to around 9V…

It’s quite complicated to troubleshoot as I do not have an oscilloscope.

I have the following configurations on the TMC6200-BOB:

  • Standalone mode
  • Driver Strength: 0.5A (following the recommendations in the introduction of the TMC6200-BOB’s datasheet)
  • Individual gate control (for 6PWM operation)

Also, I tried to visualize the PWM signals out of the Arduino using a logic analyzer, with the code provided in my previous answer. I do not see any PWM modulation with this code on the specified pins.

However, I do see PWM modulation on the driver with the blcd_driver_3pwm_standalone example!

Hey, while I don’t use the atmega 2560 myself, I looked in our code for its PWM support, and it does support 6-PWM…

But the only pins you can use are these:

9,10 on one phase
11,12 on one phase
4,13 on one phase

it doesn’t actually matter which is high and which is low, as long as you use these pairs of pins…

So looking at your code you need to be using pins 4 and 13 instead of pins 7 and 8.

1 Like

Hi!

Thank you for your help! Now I see the PWM modulation.

I’m unable to test it with a motor at the moment but I’ll get back to you once I will!

1 Like