Welcome to Hackster!
Hackster is a community dedicated to learning hardware, from beginner to pro. Join us, it's free!
Infineon Team
Published © MIT

Closed-Loop Motor Control with SimpleFOC, IFX007 and TLE5012

Learn how to achieve smooth operation with precise velocity and position control using the IFX007T and magnetic angle sensor TLE5012B.

IntermediateProtip2 hours284
Closed-Loop Motor Control with SimpleFOC, IFX007 and TLE5012

Things used in this project

Hardware components

KIT XMC47 RELAX LITE V1
Infineon KIT XMC47 RELAX LITE V1
×1
BLDC Shield IFX007T
Infineon BLDC Shield IFX007T
×1
TLE5012B E1000 MS2GO
Infineon TLE5012B E1000 MS2GO
×1
Nema23 BLDC 57blf
×1

Software apps and online services

Arduino IDE
Arduino IDE

Hand tools and fabrication machines

Soldering iron (generic)
Soldering iron (generic)
3D Printer (generic)
3D Printer (generic)
10 Pc. Jumper Wire Kit, 20 cm Long
10 Pc. Jumper Wire Kit, 20 cm Long

Story

Read more

Custom parts and enclosures

partgross_I2Scd6u9KV.stl

Sketchfab still processing.

MAGNET_HOLDER

Sketchfab still processing.

Schematics

servo_ifx007_tle5012b_steckplatine_w6bocl9pvx_BYdwT2tdnW.jpg

Code

Closed_Loop

Arduino
#include <SimpleFOC.h>
#include "TLE5012Sensor.h"

// Define SPI pins for TLE5012 sensor
#define PIN_SPI1_SS0   36                       //! Chip Select (CS) pin
#define PIN_SPI1_MOSI  37                       //! MOSI pin
#define PIN_SPI1_MISO  63                       //! MISO pin
#define PIN_SPI1_SCK   38                       //! SCK pin

// Create an instance of SPIClass3W for 3-wire SPI communication
tle5012::SPIClass3W tle5012::SPI3W1(1);         //!< SPI port 1

// Create an instance of TLE5012Sensor
TLE5012Sensor tle5012Sensor(&SPI3W1, PIN_SPI1_SS0, PIN_SPI1_MISO, PIN_SPI1_MOSI, PIN_SPI1_SCK);

// BLDC motor instance BLDCMotor(polepairs, (R), (KV))
BLDCMotor motor = BLDCMotor(4, 0.73); // 4 pole pairs, 0.73 Ω phase resistance

// Define driver pins
const int U = 11;
const int V = 10; 
const int W = 9;
const int EN_U = 6;
const int EN_V = 5;
const int EN_W = 3;

// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver3PWM driver = BLDCDriver3PWM(U, V, W,EN_U,EN_V,EN_W);

// Target variable
float target_angle = 0;

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

void setup() {


  // Initialize serial communication
  Serial.begin(115200);
  while (!Serial); // Wait for the serial port to connect (for debugging)
  SimpleFOCDebug::enable(&Serial);

  // Initialize the TLE5012 sensor
  tle5012Sensor.init();
  // Link the motor to the sensor
  motor.linkSensor(&tle5012Sensor);

  // Driver configuration
  driver.voltage_power_supply = 12; // 12V power supply
  driver.voltage_limit = 6;        // Driver voltage limit (50% of power supply)
  if (!driver.init()) {
    Serial.println("Driver init failed!");
    return;
  }

  // Link the motor and the driver
  motor.linkDriver(&driver);

  // Choose FOC modulation (optional)
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  // Set motion control loop to be used
  motor.controller = MotionControlType::angle;

  // Controller configuration
  // Velocity PI controller parameters
  motor.PID_velocity.P = 0.2f;
  motor.PID_velocity.I = 20;
  motor.PID_velocity.D = 0;
  // Maximal voltage to be set to the motor
  motor.voltage_limit = 3; // 3V limit to avoid overheating

  // Velocity low-pass filtering time constant
  motor.LPF_velocity.Tf = 0.01f;

  // Angle P controller
  motor.P_angle.P = 20;
  // Maximal velocity of the position control
  motor.velocity_limit = 5; // 5 rad/s (~50 RPM)

  // Initialize motor
  motor.init();
  // Align sensor and start FOC
  motor.initFOC();

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

  Serial.println(F("Motor ready."));
  Serial.println(F("Set the target angle using serial terminal:"));
  _delay(1000);
}

void loop() {
  // Main FOC algorithm function
  motor.loopFOC();

  // Motion control function
  motor.move(target_angle);

  // User communication
  command.run();
}

OpenLoop

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

// Define SPI pins for TLE5012 sensor
#define PIN_SPI1_SS0   36                       //! Chip Select (CS) pin
#define PIN_SPI1_MOSI  37                       //! MOSI pin
#define PIN_SPI1_MISO  63                       //! MISO pin
#define PIN_SPI1_SCK   38                       //! SCK pin

// Create an instance of SPIClass3W for 3-wire SPI communication
tle5012::SPIClass3W tle5012::SPI3W1(1);         //!< SPI port 1

// Create an instance of TLE5012Sensor
TLE5012Sensor tle5012Sensor(&SPI3W1, PIN_SPI1_SS0, PIN_SPI1_MISO, PIN_SPI1_MOSI, PIN_SPI1_SCK);


// BLDC motor instance BLDCMotor(polepairs, (R), (KV))
BLDCMotor motor = BLDCMotor(4, 0.73); // 4 pole pairs, 0.73 Ω phase resistance

// Define driver pins
const int U = 11;
const int V = 10; 
const int W = 9;
const int EN_U = 6;
const int EN_V = 5;
const int EN_W = 3;

// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver3PWM driver = BLDCDriver3PWM(U, V, W,EN_U,EN_V,EN_W);

// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6,  8);


//target variable
float target_velocity = 1;

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

void setup() {
    // use monitoring with serial 
  Serial.begin(115200);

      // Initialize the TLE5012 sensor
  tle5012Sensor.init();

  // enable more verbose output for debugging
  // comment out if not needed
  SimpleFOCDebug::enable(&Serial);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  // limit the maximal dc voltage the driver can set
  // as a protection measure for the low-resistance motors
  // this value is fixed on startup
  driver.voltage_limit = 6;
  if(!driver.init()){
    Serial.println("Driver init failed!");
    return;
  }
  // link the motor and the driver
  motor.linkDriver(&driver);

  // limiting motor movements
  // limit the voltage to be set to the motor
  // start very low for high resistance motors
  // current = voltage / resistance, so try to be well under 1Amp
  motor.voltage_limit = 3;   // [V]
 
  // open loop control config
  motor.controller = MotionControlType::velocity_openloop;

  // init motor hardware
  if(!motor.init()){
    Serial.println("Motor init failed!");
    return;
  }

  // add target command T
  command.add('T', doTarget, "target velocity");
  command.add('L', doLimit, "voltage limit");

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

void loop() {
      // Update the sensor reading
    tle5012Sensor.update();

    // Display the angle and the angular velocity to the terminal
    Serial.print(tle5012Sensor.getAngle());
    Serial.print("\t");
    Serial.println(tle5012Sensor.getVelocity());

  // open loop velocity movement
  // using motor.voltage_limit and motor.velocity_limit
  // to turn the motor "backwards", just set a negative target_velocity
  motor.move(target_velocity);

  // user communication
  command.run();
}

TLE5012Sensor.h

C/C++
#ifndef TLE5012SENSOR_H
#define TLE5012SENSOR_H

#include <SimpleFOC.h>
#include <tlx5012-arduino.hpp>

using namespace tle5012;

class TLE5012Sensor : public Sensor {
public:
    // Constructor
    TLE5012Sensor(SPIClass3W* spi, int csPin, int misoPin, int mosiPin, int sckPin);

    // Initialize the sensor hardware
    void init();

    // Get the current shaft angle from the sensor hardware
    float getSensorAngle();

private:
    Tle5012Ino _sensor; // Instance of the TLE5012 sensor
    errorTypes _checkError; // Variable to store sensor initialization errors
};

#endif

TLE5012Sensor.cpp

C/C++
#include "TLE5012Sensor.h"

// Constructor
TLE5012Sensor::TLE5012Sensor(SPIClass3W* spi, int csPin, int misoPin, int mosiPin, int sckPin)
    : _sensor(spi, csPin, misoPin, mosiPin, sckPin) {}

// Initialize the sensor hardware
void TLE5012Sensor::init() {
    _checkError = _sensor.begin();
    if (_checkError != NO_ERROR) {
        Serial.print("TLE5012 sensor initialization error: ");
        Serial.println(_checkError, HEX);
    } else {
        Serial.println("TLE5012 sensor initialized successfully!");
    }
}

// Get the current shaft angle from the sensor hardware
float TLE5012Sensor::getSensorAngle() {
    double angle = 0.0;
    _sensor.getAngleValue(angle); // Read the angle from the sensor

    // Convert the angle to radians and adjust it to the range [0, 2]
    float angleRad = (angle + 180.0) * (M_PI / 180.0); // Convert degrees to radians
    if (angleRad > 2 * M_PI) {
        angleRad -= 2 * M_PI; // Ensure the angle is within 0 to 2
    }
    return angleRad;
}

TLE5012 Arduino Library

Arduino library for TLE5012B magnetic angle sensor.

XMC for Arduino

Arduino core for XMC microcontroller series.

Credits

Infineon Team
100 projects • 157 followers
Contact
Thanks to SimpleFOC.

Comments

Please log in or sign up to comment.