MotorGo Mini

MotorGo Mini

The MotorGo Mini is a small, low-cost, low-power motor controller that can be used to control a two motors.

https://motorgo.net

It’s pretty sweet and the component provides the implementation of the two channel FOC motor controller, along with other peripheral classes such as the ADC, LEDs, and I2C.

API Reference

Header File

Classes

class MotorGoMini : public espp::BaseComponent

This class acts as a board support component for the MotorGo-Mini board. It provides a high-level interface to the board’s functionality. The MotorGo-Mini board is a motor driver board that can drive two DC motors. More information about the board can be found at: https://github.com/Every-Flavor-Robotics/motorgo-mini-hardware

High level overview of the board:

  • ESP32s3 module

  • Two LEDs (yellow and red)

  • Two BLDC motor drivers (TMC6300)

  • Two magnetic encoders (connected via two JST-SH 5 pin connectors to EncoderGo boards) (SPI2_HOST)

  • Two Qwiic connectors for I2C communication (I2C0)

  • Current sense resistors for each motor on the U and W phases NOTE: on the MotorGo-Mini v1.3, the M2 motor sense is swapped in the schematic, with U and W swapped

The class is a singleton and can be accessed using the get() method.

MotorGo-Mini Example

  auto &motorgo_mini = espp::MotorGoMini::get();
  motorgo_mini.set_log_level(espp::Logger::Verbosity::INFO);

  // set the configuration for the motors For simplicity, we'll copy the
  // defaults and modify them, but you can also just make a type of
  // espp::MotorGoMini::BldcMotor::Config
  auto motor1_config = motorgo_mini.default_motor1_config;
  motor1_config.phase_resistance = 4.0f; // ohms
  motor1_config.current_limit = 1.0f;    // amps
  // velocity PID config:
  motor1_config.velocity_pid_config.kp = 0.020f;
  motor1_config.velocity_pid_config.ki = 0.700f;
  motor1_config.velocity_pid_config.kd = 0.000f;
  // angle PID config:
  motor1_config.angle_pid_config.kp = 5.000f;
  motor1_config.angle_pid_config.ki = 1.000f;
  motor1_config.angle_pid_config.kd = 0.000f;

  auto motor2_config = motorgo_mini.default_motor2_config;
  motor2_config.phase_resistance = 4.0f; // ohms
  motor2_config.current_limit = 1.0f;    // amps
  // velocity PID config:
  motor2_config.velocity_pid_config.kp = 0.020f;
  motor2_config.velocity_pid_config.ki = 0.700f;
  motor2_config.velocity_pid_config.kd = 0.000f;
  // angle PID config:
  motor2_config.angle_pid_config.kp = 5.000f;
  motor2_config.angle_pid_config.ki = 1.000f;
  motor2_config.angle_pid_config.kd = 0.000f;

  // now initialize the motors
  motorgo_mini.init_motor_channel_1(motor1_config);
  motorgo_mini.init_motor_channel_2(motor2_config);

  // get the motor objects (shared pointers) for use in the script
  auto motor1 = motorgo_mini.motor1();
  auto motor2 = motorgo_mini.motor2();

  static constexpr uint64_t core_update_period_us = 1'000;                  // microseconds
  static constexpr float core_update_period = core_update_period_us / 1e6f; // seconds

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

  logger.info("Setting motion control type to {}", motion_control_type);
  motor1->set_motion_control_type(motion_control_type);
  motor2->set_motion_control_type(motion_control_type);

  motor1->enable();
  motor2->enable();

  std::atomic<float> target1 = 60.0f;
  std::atomic<float> target2 = 60.0f;
  static bool target_is_angle =
      motion_control_type == espp::detail::MotionControlType::ANGLE ||
      motion_control_type == espp::detail::MotionControlType::ANGLE_OPENLOOP;
  // Function for initializing the target based on the motion control type
  auto initialize_target = [&]() {
    if (target_is_angle) {
      target1 = motor1->get_shaft_angle();
      target2 = motor2->get_shaft_angle();
    } else {
      target1 = 50.0f * espp::RPM_TO_RADS;
      target2 = 50.0f * espp::RPM_TO_RADS;
    }
  };
  // run it once
  initialize_target();

  auto dual_motor_fn = [&]() -> bool {
    motor1->loop_foc();
    motor1->move(target1);
    motor2->loop_foc();
    motor2->move(target2);
    return false; // don't want to stop the task
  };

  auto dual_motor_timer = espp::HighResolutionTimer({.name = "Motor Timer",
                                                     .callback = dual_motor_fn,
                                                     .log_level = espp::Logger::Verbosity::WARN});
  dual_motor_timer.periodic(core_update_period_us);

  static constexpr float sample_freq_hz = 100.0f;
  static constexpr float filter_cutoff_freq_hz = 5.0f;
  static constexpr float normalized_cutoff_frequency =
      2.0f * filter_cutoff_freq_hz / sample_freq_hz;
  static constexpr size_t ORDER = 2;
  // NOTE: using the Df2 since it's hardware accelerated :)
  using Filter = espp::ButterworthFilter<ORDER, espp::BiquadFilterDf2>;
  Filter filter1({.normalized_cutoff_frequency = normalized_cutoff_frequency});
  Filter filter2({.normalized_cutoff_frequency = normalized_cutoff_frequency});

  // if it's a velocity setpoint then target is RPM
  fmt::print("%time(s), "
             "motor 1 target, " // target is either RPM or radians
             "motor 1 angle (radians), "
             "motor 1 speed (rpm), "
             "motor 2 target, " // target is either RPM or radians
             "motor 2 angle (radians), "
             "motor 2 speed (rpm)\n");

  // make the task to periodically poll the encoders and print the state. NOTE:
  // the encoders run their own tasks to maintain state, so we're just polling
  // the current state.
  auto logging_fn = [&](std::mutex &m, std::condition_variable &cv) {
    static auto start = std::chrono::high_resolution_clock::now();
    auto now = std::chrono::high_resolution_clock::now();
    auto seconds = std::chrono::duration<float>(now - start).count();
    auto _target1 = target1.load();
    if (!target_is_angle)
      _target1 *= espp::RADS_TO_RPM;
    auto _target2 = target2.load();
    if (!target_is_angle)
      _target2 *= espp::RADS_TO_RPM;
    auto rpm1 = filter1(motor1->get_shaft_velocity() * espp::RADS_TO_RPM);
    auto rpm2 = filter2(motor2->get_shaft_velocity() * espp::RADS_TO_RPM);
    auto rads1 = motor1->get_shaft_angle();
    auto rads2 = motor2->get_shaft_angle();
    fmt::print("{:.3f}, {:.3f}, {:.3f}, {:.3f}, {:.3f}, {:.3f}, {:.3f}\n", seconds, _target1, rads1,
               rpm1, _target2, rads2, rpm2);
    // NOTE: sleeping in this way allows the sleep to exit early when the
    // task is being stopped / destroyed
    {
      std::unique_lock<std::mutex> lk(m);
      cv.wait_for(lk, 10ms);
    }
    // don't want to stop the task
    return false;
  };
  auto logging_task = espp::Task({.callback = logging_fn,
                                  .task_config =
                                      {
                                          .name = "Logging Task",
                                          .stack_size_bytes = 5 * 1024,
                                      },
                                  .log_level = espp::Logger::Verbosity::WARN});
  logging_task.start();

  std::this_thread::sleep_for(1s);
  logger.info("Starting target task");

  enum class IncrementDirection { DOWN = -1, HOLD = 0, UP = 1 };
  static IncrementDirection increment_direction1 = IncrementDirection::UP;
  static IncrementDirection increment_direction2 = IncrementDirection::DOWN;

  auto update_target = [&](auto &target, auto &increment_direction) {
    float max_target = target_is_angle ? (2.0f * M_PI) : (200.0f * espp::RPM_TO_RADS);
    float target_delta =
        target_is_angle ? (M_PI / 4.0f) : (50.0f * espp::RPM_TO_RADS * core_update_period);
    // update target
    if (increment_direction == IncrementDirection::UP) {
      target += target_delta;
      if (target >= max_target) {
        increment_direction = IncrementDirection::DOWN;
      }
    } else if (increment_direction == IncrementDirection::DOWN) {
      target -= target_delta;
      if (target <= -max_target) {
        increment_direction = IncrementDirection::UP;
      }
    }
  };

  // make a task which will update the target (velocity or angle)
  auto target_task_fn = [&](std::mutex &m, std::condition_variable &cv) {
    auto delay = std::chrono::duration<float>(target_is_angle ? 1.0f : core_update_period);
    auto start = std::chrono::high_resolution_clock::now();
    update_target(target1, increment_direction1);
    update_target(target2, increment_direction2);
    // NOTE: sleeping in this way allows the sleep to exit early when the
    // task is being stopped / destroyed
    {
      std::unique_lock<std::mutex> lk(m);
      cv.wait_until(lk, start + delay);
    }
    // don't want to stop the task
    return false;
  };
  auto target_task = espp::Task({
      .callback = target_task_fn,
      .task_config = {.name = "Target Task"},
  });
  target_task.start();

  logger.info("Initializing the button");
  auto on_button_pressed = [&](const auto &event) {
    if (event.active) {
      logger.info("Button pressed, changing motion control type");
      // switch between ANGLE and VELOCITY
      if (motion_control_type == espp::detail::MotionControlType::ANGLE ||
          motion_control_type == espp::detail::MotionControlType::ANGLE_OPENLOOP) {
        motion_control_type = espp::detail::MotionControlType::VELOCITY;
        target_is_angle = false;
      } else {
        motion_control_type = espp::detail::MotionControlType::ANGLE;
        target_is_angle = true;
      }
      initialize_target();
      motor1->set_motion_control_type(motion_control_type);
      motor2->set_motion_control_type(motion_control_type);
    } else {
      logger.info("Button released");
    }
  };
  motorgo_mini.initialize_button(on_button_pressed);

  // now loop forever (do nothing)
  while (true) {
    std::this_thread::sleep_for(1s);
  }

Public Types

using button_callback_t = espp::Interrupt::event_callback_fn

Alias for the button callback function.

using Encoder = espp::Mt6701<espp::Mt6701Interface::SSI>

Alias for the encoder type.

using BldcMotor = espp::BldcMotor<espp::BldcDriver, Encoder>

Alias for the BLDC motor type.

using VelocityFilter = espp::SimpleLowpassFilter

Alias for the velocity filter type.

using AngleFilter = espp::SimpleLowpassFilter

Alias for the angle filter type.

Public Functions

I2c &get_external_i2c()

Get a reference to the external I2C bus

Returns

A reference to the external I2C bus

espp::Interrupt &interrupts()

Get a reference to the interrupts

Returns

A reference to the interrupts

bool initialize_button(const button_callback_t &callback = nullptr)

Initialize the button

Parameters

callback – The callback function to call when the button is pressed

Returns

true if the button was successfully initialized, false otherwise

bool button_state() const

Get the button state

Returns

The button state (true = button pressed, false = button released)

espp::Led::ChannelConfig &yellow_led()

Get a reference to the yellow LED channel (channel 0)

Returns

A reference to the yellow LED channel (channel 0)

espp::Led::ChannelConfig &led_channel0()

Get a reference to the yellow LED channel (channel 0)

Returns

A reference to the yellow LED channel (channel 0)

void set_yellow_led_duty(float duty)

Set the duty cycle of the yellow LED

Note

The duty cycle is a percentage of the maximum duty cycle (which is 100.0) 0.0 is off, 100.0 is fully on

Note

For this function to have an effect, the LED timer must NOT be running (i.e. stop_breathing() must be called)

Parameters

duty – The duty cycle of the yellow LED (0.0 - 100.0)

espp::Led::ChannelConfig &red_led()

Get a reference to the red LED channel (channel 1)

Returns

A reference to the red LED channel (channel 1)

espp::Led::ChannelConfig &led_channel1()

Get a reference to the red LED channel (channel 1)

Returns

A reference to the red LED channel (channel 1)

void set_red_led_duty(float duty)

Set the duty cycle of the red LED

Note

The duty cycle is a percentage of the maximum duty cycle (which is 100.0) 0.0 is off, 100.0 is fully on

Note

For this function to have an effect, the LED timer must NOT be running (i.e. stop_breathing() must be called)

Parameters

duty – The duty cycle of the red LED (0.0 - 100.0)

espp::Led &led()

Get a reference to the LED object which controls the LEDs

Returns

A reference to the Led object

espp::Gaussian &gaussian()

Get a reference to the Gaussian object which is used for breathing the LEDs.

Returns

A reference to the Gaussian object

void start_breathing()

Start breathing the LEDs

This function starts the LED timer which will periodically update the LED duty cycle using the gaussian to create a breathing efect.

void stop_breathing()

Stop breathing the LEDs

This function stops the LED timer which will stop updating the LED duty cycle. It will also set the LED duty cycle to 0, effectively turning off the LEDs.

espp::OneshotAdc &adc1()

Get a reference to the ADC_UNIT_1 OneshotAdc object

Returns

A reference to the ADC_UNIT_1 OneshotAdc object

espp::OneshotAdc &adc2()

Get a reference to the ADC_UNIT_2 OneshotAdc object

Returns

A reference to the ADC_UNIT_2 OneshotAdc object

void init_motor_channel_1 (const BldcMotor::Config &motor_config, const DriverConfig &driver_config={.power_supply_voltage=5.0f,.limit_voltage=5.0f})

Initialize the MotorGo-Mini’s components for motor channel 1

This function initializes the encoder, driver, and motor for motor channel 1. This consists of initializing encoder1, motor_driver, and motor1.

Parameters
  • motor_config – The motor configuration

  • driver_config – The driver configuration

void init_motor_channel_2 (const BldcMotor::Config &motor_config, const DriverConfig &driver_config={.power_supply_voltage=5.0f,.limit_voltage=5.0f})

Initialize the MotorGo-Mini’s components for motor channel 2

This function initializes the encoder, driver and motor for motor channel 2. This consists of initializing encoder2, motor2_driver, and motor2.

Parameters
  • motor_config – The motor configuration

  • driver_config – The driver configuration

std::shared_ptr<espp::BldcDriver> motor1_driver()

Get a shared pointer to the motor 1 driver

Returns

A shared pointer to the motor 1 driver

std::shared_ptr<espp::BldcDriver> motor2_driver()

Get a shared pointer to the motor 2 driver

Returns

A shared pointer to the motor 2 driver

std::shared_ptr<BldcMotor> motor1()

Get a shared pointer to the motor 1

Returns

A shared pointer to the motor 1

std::shared_ptr<BldcMotor> motor2()

Get a shared pointer to the motor 2

Returns

A shared pointer to the motor 2

VelocityFilter &motor1_velocity_filter()

Get a reference to the motor 1 velocity filter

Returns

A reference to the motor 1 velocity filter

AngleFilter &motor1_angle_filter()

Get a reference to the motor 1 angle filter

Returns

A reference to the motor 1 angle filter

VelocityFilter &motor2_velocity_filter()

Get a reference to the motor 2 velocity filter

Returns

A reference to the motor 2 velocity filter

AngleFilter &motor2_angle_filter()

Get a reference to the motor 2 angle filter

Returns

A reference to the motor 2 angle filter

std::shared_ptr<Encoder> encoder1()

Get a shared pointer to the encoder 1

Returns

A shared pointer to the encoder 1

std::shared_ptr<Encoder> encoder2()

Get a shared pointer to the encoder 2

Returns

A shared pointer to the encoder 2

void reset_encoder1_accumulator()

Reset the encoder 1 accumulator

This function resets the encoder 1 accumulator to 0. This will reset the encoder’s position to be within the range of 0 to 2*pi.

void reset_encoder2_accumulator()

Reset the encoder 2 accumulator

This function resets the encoder 2 accumulator to 0. This will reset the encoder’s position to be within the range of 0 to 2*pi.

float motor1_current_u_amps()

Get the current sense value for motor 1 phase U

Returns

The current sense value for motor 1 phase U in amps

float motor1_current_w_amps()

Get the current sense value for motor 1 phase W

Returns

The current sense value for motor 1 phase W in amps

float motor2_current_u_amps()

Get the current sense value for motor 2 phase U

Returns

The current sense value for motor 2 phase U in amps

float motor2_current_w_amps()

Get the current sense value for motor 2 phase W

Returns

The current sense value for motor 2 phase W in amps

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

Public Members

const BldcMotor::Config default_motor1_config

Default configuration for the MotorGo-Mini’s BLDC motor on channel 1.

const BldcMotor::Config default_motor2_config

Default configuration for the MotorGo-Mini’s BLDC motor on channel 2.

Public Static Functions

static inline MotorGoMini &get()

Access the singleton instance of the MotorGoMini class.

Returns

Reference to the singleton instance of the MotorGoMini class

struct DriverConfig

Driver Configuration for the MotorGo-Mini Motor Driver(s)

Public Members

float power_supply_voltage

The power supply voltage in volts.

float limit_voltage

The limit voltage in volts.