BLDC Motor

The BldcMotor implements the Field-Oriented Control (FOC) algorithm with support for multiple transforms to drive voltage (such as Sinusoidal and Space Vector). It supports the following motion control configurations (which can be changed dynamically):

  • Closed-loop angle

  • Closed-loop velocity

  • Open-loop angle

  • Open-loop velocity

Note: currently the code has some support for Torque control, but that requires current sense - for which I don’t yet have the hardware to support the development of.

The BldcMotor should be configured with a BldcDriver and optional Sensor (for angle & speed of the motor), and optional CurrentSensor (for measuring the phase currents of the motor and providing torque control).

API Reference

Header File

Classes

template<DriverConcept D, SensorConcept S, CurrentSensorConcept CS = DummyCurrentSense>
class BldcMotor : public espp::BaseComponent

Motor control class for a Brushless DC (BLDC) motor, implementing the field-oriented control (FOC) algorithm. Must be provided a driver object / type, and optionally a position/velocity sensor object/type and optionally a current sensor object / type.

Example Usage

    // now make the mt6701 which decodes the data
    using Encoder = espp::Mt6701<>;
    std::shared_ptr<Encoder> mt6701 = std::make_shared<Encoder>(
        Encoder::Config{.write = std::bind(&espp::I2c::write, &i2c, std::placeholders::_1,
                                           std::placeholders::_2, std::placeholders::_3),
                        .read = std::bind(&espp::I2c::read, &i2c, std::placeholders::_1,
                                          std::placeholders::_2, std::placeholders::_3),
                        .velocity_filter = nullptr, // no filtering
                        .update_period = std::chrono::duration<float>(core_update_period),
                        .log_level = espp::Logger::Verbosity::WARN});

    // now make the bldc driver
    std::shared_ptr<espp::BldcDriver> driver =
        std::make_shared<espp::BldcDriver>(espp::BldcDriver::Config{
            // this pinout is configured for the TinyS3 connected to the
            // TMC6300-BOB in the BLDC Motor Test Stand
            .gpio_a_h = 1,
            .gpio_a_l = 2,
            .gpio_b_h = 3,
            .gpio_b_l = 4,
            .gpio_c_h = 5,
            .gpio_c_l = 21,
            .gpio_enable = 34, // connected to the VIO/~Stdby pin of TMC6300-BOB
            .gpio_fault = 36,  // connected to the nFAULT pin of TMC6300-BOB
            .power_supply_voltage = 5.0f,
            .limit_voltage = 5.0f,
            .log_level = espp::Logger::Verbosity::WARN});

    // now make the bldc motor
    using BldcMotor = espp::BldcMotor<espp::BldcDriver, Encoder>;
    auto motor = BldcMotor(BldcMotor::Config{
        // measured by setting it into ANGLE_OPENLOOP and then counting how many
        // spots you feel when rotating it.
        .num_pole_pairs = 7,
        .phase_resistance =
            5.0f, // tested by running velocity_openloop and seeing if the veloicty is ~correct
        .kv_rating =
            320, // tested by running velocity_openloop and seeing if the velocity is ~correct
        .current_limit = 1.0f,        // Amps
        .zero_electric_offset = 0.0f, // set to zero to always calibrate, since this is a test
        .sensor_direction = espp::detail::SensorDirection::UNKNOWN, // set to unknown to always
                                                                    // calibrate, since this is a
                                                                    // test
        .foc_type = espp::detail::FocType::SPACE_VECTOR_PWM,
        .driver = driver,
        .sensor = mt6701,
        .velocity_pid_config =
            {
                .kp = 0.010f,
                .ki = 1.000f,
                .kd = 0.000f,
                .integrator_min = -1.0f, // same scale as output_min (so same scale as current)
                .integrator_max = 1.0f,  // same scale as output_max (so same scale as current)
                .output_min = -1.0, // velocity pid works on current (if we have phase resistance)
                .output_max = 1.0,  // velocity pid works on current (if we have phase resistance)
            },
        .angle_pid_config =
            {
                .kp = 7.000f,
                .ki = 0.300f,
                .kd = 0.010f,
                .integrator_min = -10.0f, // same scale as output_min (so same scale as velocity)
                .integrator_max = 10.0f,  // same scale as output_max (so same scale as velocity)
                .output_min = -20.0,      // angle pid works on velocity (rad/s)
                .output_max = 20.0,       // angle pid works on velocity (rad/s)
            },
        .log_level = espp::Logger::Verbosity::DEBUG});

    static const auto motion_control_type = espp::detail::MotionControlType::VELOCITY;
    // static const auto motion_control_type = espp::detail::MotionControlType::ANGLE;
    // static const auto motion_control_type = espp::detail::MotionControlType::VELOCITY_OPENLOOP;
    // static const auto motion_control_type = espp::detail::MotionControlType::ANGLE_OPENLOOP;

    // Set the motion control type and create a target for the motor (will be
    // updated in the target update task below)
    motor.set_motion_control_type(motion_control_type);
    std::atomic<float> target = 0;

    // enable the motor
    motor.enable();

    auto motor_task_fn = [&motor, &target]() -> bool {
      if (motion_control_type == espp::detail::MotionControlType::VELOCITY ||
          motion_control_type == espp::detail::MotionControlType::VELOCITY_OPENLOOP) {
        // if it's a velocity setpoint, convert it from RPM to rad/s
        motor.move(target * espp::RPM_TO_RADS);
      } else {
        motor.move(target);
      }
      // command the motor
      motor.loop_foc();
      // don't want to stop the task
      return false;
    };
    auto motor_timer = espp::HighResolutionTimer({.name = "Motor Timer",
                                                  .callback = motor_task_fn,
                                                  .log_level = espp::Logger::Verbosity::WARN});
    motor_timer.periodic(core_update_period_us);

Note

This is a port (with some modifications) of the excellent work by SimpleFOC - https://simplefoc.com

Public Types

typedef std::function<float(float raw)> filter_fn

Filter the raw input sample and return it.

Param raw

Most recent raw sample measured.

Return

Filtered output from the input.

Public Functions

inline explicit BldcMotor(const Config &config)

Create and initialize the BLDC motor, running through any necessary sensor calibration.

inline ~BldcMotor()

Destroy the motor, making sure to disable it first to ensure power is cutoff.

inline bool is_enabled() const

Check if the motor is enabled.

Returns

True if the motor is enabled, false otherwise.

inline void enable()

Enable the controller and driver output.

inline void disable()

Disable the controller and driver output.

inline void initialize(float zero_electric_offset = 0, detail::SensorDirection sensor_direction = detail::SensorDirection::UNKNOWN)

Initialize the motor, running through any necessary sensor calibration.

Note

This function will enable the motor, run through the necessary calibration steps, and then disable the motor.

Note

This function is automatically called in the constructor if auto_init is set to true. Otherwise, it must be called manually before the motor can be used.

Parameters
  • zero_electric_offset – The zero electrical offset for the motor.

  • sensor_direction – The direction of the sensor.

inline void set_motion_control_type(detail::MotionControlType motion_control_type)

Update the motoion control scheme the motor control loop uses.

Parameters

motion_control_type – New motion control to use.

inline void set_phase_voltage(float uq, float ud, float el_angle)

Method using FOC to set Uq to the motor at the optimal angle. Heart of the FOC algorithm.

Parameters
  • uq – Current voltage in q axis to set to the motor

  • ud – Current voltage in d axis to set to the motor

  • el_angle – current electrical angle of the motor

inline float get_shaft_angle()

Return the shaft angle, in radians.

Returns

Motor shaft angle in radians.

inline float get_shaft_velocity()

Return the shaft velocity, in radians per second (rad/s).

Returns

Motor shaft velocity (rad/s).

inline float get_electrical_angle()

Get the electrical angle of the motor - using the mechanical angle, the number of pole pairs, and the zero electrical angle.

Returns

The electrical angle of the motor (in radians)

inline void loop_foc()

Main FOC loop for implementing the torque control, based on the configured detail::TorqueControlType.

Note

Only detail::TorqueControlType::VOLTAGE is supported right now, because the other types require current sense.

inline void move(float new_target)

Main motion control loop implementing the closed-loop and open-loop angle & velocity control.

Note

Units are based on the detail::MotionControlType; radians if it’s detail::MotionControlType::ANGLE or detail::MotionControlType::ANGLE_OPENLOOP, radians/second if it’s detail::MotionControlType::VELOCITY or detail::MotionControlType::VELOCITY_OPENLOOP, Nm if it’s detail::MotionControlType::TORQUE.

Parameters

new_target – The new target for the configured detail::MotionControlType.

inline const std::string &get_name() const

Get the name of the component

Note

This is the tag of the logger

Returns

A const reference to the name of the component

inline void set_log_tag(const std::string_view &tag)

Set the tag for the logger

Parameters

tag – The tag to use for the logger

inline espp::Logger::Verbosity get_log_level() const

Get the log level for the logger

Returns

The verbosity level of the logger

inline void set_log_level(espp::Logger::Verbosity level)

Set the log level for the logger

Parameters

level – The verbosity level to use for the logger

inline void set_log_verbosity(espp::Logger::Verbosity level)

Set the log verbosity for the logger

See also

set_log_level

Note

This is a convenience method that calls set_log_level

Parameters

level – The verbosity level to use for the logger

inline espp::Logger::Verbosity get_log_verbosity() const

Get the log verbosity for the logger

See also

get_log_level

Note

This is a convenience method that calls get_log_level

Returns

The verbosity level of the logger

inline void set_log_rate_limit(std::chrono::duration<float> rate_limit)

Set the rate limit for the logger

Note

Only calls to the logger that have _rate_limit suffix will be rate limited

Parameters

rate_limit – The rate limit to use for the logger

struct Config

BLDC Motor / FOC configuration structure.

Public Members

size_t num_pole_pairs

Number of pole pairs in the motor.

float phase_resistance

Motor phase resistance (ohms).

float kv_rating

Motor KV rating (1/K_bemf) - rpm/V

float phase_inductance = {0}

Motor phase inductance (Henries).

float current_limit = {1.0f}

Current limit (Amps) for the controller.

float velocity_limit = {1000.0f}

Velocity limit (RPM) for the controller.

detail::FocType foc_type = {detail::FocType::SPACE_VECTOR_PWM}

How the voltage for the phases should be calculated.

detail::TorqueControlType torque_controller = {detail::TorqueControlType::VOLTAGE}

Torque controller type.

std::shared_ptr<D> driver

Driver for low-level setting of phase PWMs.

std::shared_ptr<S> sensor

Sensor for measuring position / speed.

bool run_sensor_update{false}

Runs the sensor::update() in the loop_foc() function. If false, the sensor must be updated elsewhere (e.g. within a sensor task).

std::shared_ptr<CS> current_sense{nullptr}

Sensor for measuring current through the motor.

Pid::Config current_pid_config  {.kp = 0,.ki = 0,.kd = 0,.integrator_min = 0,.integrator_max = 0,.output_min = 0,.output_max = 0}

PID configuration for current (amps) pid controller.

Pid::Config velocity_pid_config  {.kp = 0,.ki = 0,.kd = 0,.integrator_min = 0,.integrator_max = 0,.output_min = 0,.output_max =0}

PID configuration for velocity pid controller.

Pid::Config angle_pid_config  {.kp = 0,.ki = 0,.kd = 0,.integrator_min = 0,.integrator_max = 0,.output_min = 0,.output_max =0}

PID configuration for angle pid controller.

filter_fn q_current_filter = {nullptr}

Optional filter added to the sensed q current.

filter_fn d_current_filter = {nullptr}

Optional filter added to the sensed d current.

filter_fn velocity_filter = {nullptr}

Optional filter added to the sensed velocity.

filter_fn angle_filter = {nullptr}

Optional filter added to the sensed angle.

bool auto_init = {true}

Automatically initialize the motor. Ensure all necessary objects and communications have been initialized before this object has been constructed, or this will fail.

Logger::Verbosity log_level = {Logger::Verbosity::WARN}

Log verbosity for the Motor.

Header File

Header File