RC ESC based Brushed DC motor closed loop control

Hey everyone, thanks for this great library, and I look forward to contributing.
I am working with some brushless and brushed DC motors and would like to leverage the SimpleFOC ecosystem to control both and integrate with ROS. Right now, my issue relates to the closed loop brushed DC motor control using the Simple FOC DC motor library (GitHub - simplefoc/Arduino-FOC-dcmotor: Control DC motors using SimpleFOC's infrastructure). I want to use it to control a brushed motor through an RC ESC’s PWM from my microcontroller. I have a rotary quadrature encoder and an AS5047P magnetic encoder to use, but I would first like to test in open-loop mode. The library references this kind of setup here (Arduino-FOC-dcmotor/src/drivers at main · simplefoc/Arduino-FOC-dcmotor · GitHub), with the DCDriver1PWM driver to control both speed and direction, which is common for Servos and RC ESCs. However, I am having difficulties setting this up. My ESC operates at 50Hz PWM frequency with 1000 microseconds being full reverse and 2000 microseconds signaling full forward throttle with 1500 microseconds being the neutral point (called threshold) in the library. The input voltage to the ESC/motor is about 6 volts. I should also note that I am able to control the motors using the standard Arduino IDE Servo library (e.g. using Servo.write(0-180 degrees) or Servo.writeMicroseconds(1000-2000)). I have a Raspberry Pi Pico, Teensy 4.1, and Arduino Mega 2560 for testing. My questions are as follows:

  1. Is it possible to use the library/Simple FOC with my setup?
  2. If so, how can I set this up as the documentation does not specify units, e.g. for threshold, setPwm function, etc?
  3. How does the library write to the DCDriver1PWM driver? Using <Servo.h> or analogWrite?
  4. What are the expected values for the setPwm function?

If all else works, then I will try the other control methods. Thanks for your help.

I’ll copy here what I wrote in discord :slight_smile:

Hi @privvyledge , welcome to SimpleFOC!

Firstly, what you want to do with the brushed DC motor should be quite possible. I made a test setup using only very cheap components (DC motor and magnetic sensor), and was able to regulate the position of the motor as if it were a servo. Velocity control via 1-PWM should be possible also.

However, I should give you fair warning: our SimpleDC library is very new, so in a way you would be helping us to test it… :grimacing: so if you’re expecting a fully ready and tested piece of software here, I have to disappoint. That’s for the DC-motors part. For the brushless motors the SimpleFOC library has been around a while and is well tested.

So this also means the documentation of the DCDriver library is not yet very detailed.

The DCDriver1PWM is intended to work a bit like a RC servo controller, but I have not tested it yet, and therefore I may not have considered all the needs… lets see if it can work for you.

The setPwm() works like this: the idea is that the value represents a voltage, based on the driver.voltage_power_supply

So if your driver.voltage_power_supply is 10V, and you call setPwm(5.0); then the resulting PWM duty cycle should be 50%.

When controlling this type of servo with 50Hz, you have 20000us period time. If it works with 1000 - 1500 - 2000us timings, that corresponds to 5%, 7.5% and 10% of 20000us, so translating that into voltages for setPwm() it means you would operate the DCDriver1PWM using voltages between 9V and 9.5V, with the middle point at 9.25V.

That’s assuming a 10V power supply. More generally, you would choose the setpoints as:

float full_rev = driver.voltage_power_supply * 0.95; // 1000us/20000us = 5%
float full_fwd = driver.voltage_power_supply * 0.9; // 2000us/20000us = 10%
float zero_point = driver.voltage_power_supply * 0.925; // 20000us/1500us = 7.5%

(this is assuming the servo has active-low polarity) (edited)

How does the library write to the DCDriver1PWM driver? Using <Servo.h> or analogWrite?

No, neither, you just use driver.setPwm(); So you would configure and init the driver in your setup() routine, and use it via driver.setPwm(some_voltage); in the rest of the code.

You can also look at using our DCMotor class, but I am not sure that it can deal with the PWM range you need at the moment. I think it will use 0-10V on the driver1PWM which is not what you need.

#define PIN_PWM 1
#define PIN_EN 5
#define THESHOLD 0.925f

DCDriver driver = DCDriver1PWM(PIN_PWM, THESHOLD, PIN_EN);

void setup() {
  driver.voltage_power_supply = 10.0f;
  driver.init();
}

void loop() {
   ...
    driver.setPwm(9.43);
   ...
}

I’d be very happy to help you get this working, as it would help us a lot to get feedback and test results for the DC motor library :slight_smile:

Thank you very much for the quick response. I understand that the DC motor class is new and I would need to test it so it can be improved. In fact, that’s the reason I am trying to use this library as opposed to other methods to perform closed-loop brushed motor control. I also have a few other types of brushed motor drivers that I will use to test the other drivers in the simple DC motor library. While I am waiting for a 2S battery to use with the ESC, I am using an RC servo motor to test since it uses the same type of command interface I need. For some more context, it’s a Traxxas 4-Tec 2.0 chassis with the XL-5 waterproof ESC connected to the Titan 12-turn 550 modified motor and the 2075 Traxxas servo.

Here’s the code:

#include <Arduino.h>
#include <SimpleFOC.h>
// #include "SimpleFOCDrivers.h"
#include "SimpleDCMotor.h"

#define PIN_PWM 9
#define THRESHOLD 0.925f  // range: [0, 1].
#define MAX_DUTY 0.9f  // range: [0, 1]. Maybe 0.05f
#define MIN_DUTY 0.95f  // range: [0, 1]. Maybe 0.1f
#define NEUTRAL_DUTY 0.925f  // range: [0, 1]. Maybe 0.075
#define SUPPLY_VOLTAGE 6.0f  // volts

// DCMotor motor = DCMotor();

DCDriver1PWM driver = DCDriver1PWM(PIN_PWM, THRESHOLD);

const float minSteering = SUPPLY_VOLTAGE * MAX_DUTY;  // microseconds: 1000
const float maxSteering = SUPPLY_VOLTAGE * MIN_DUTY;  // microseconds: 2000
const float neutralSteering = SUPPLY_VOLTAGE * NEUTRAL_DUTY;  // microseconds: 1500

// Setup analog joystick
const int joystick_switch_pin = 15;  // digital pin connected to switch output
const int joystick_Rx_pin = A1; // analog pin connected to X output
const int joystick_Ry_pin = A0; // analog pin connected to Y output

int throttle_value = neutralSteering; // throttle input
int steering_value = neutralSteering; // steering input
int switch_value;  // josytick pin

int rx_min = 7;
int rx_max = 1023;
int ry_min = 6;
int ry_max = 1023;

float fmap(float toMap, float in_min, float in_max, float out_min, float out_max) {
  return (toMap - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}

void setup() {
  // basic driver setup - set power supply voltage
  driver.voltage_power_supply = SUPPLY_VOLTAGE;
  // driver.pwm_frequency = 50;
  // initialize driver
  driver.init();
}

void loop() {
  steering_value = analogRead(joystick_Ry_pin);  // steering input
  steering_value = constrain(steering_value, ry_min, ry_max);
  steering_value = fmap(steering_value, ry_min, ry_max, minSteering, maxSteering);
  // driver.setPwm(steering_value); // 3.0f. 3 Volts
  driver.setPwm(neutralSteering); // 3.0f. 3 Volts
  delay(50);
}

  1. The servo power supply in this case is 6.0 volts.
  2. When uploaded to my Raspberry Pi Pico, the steering just turns full left and maintains it, i.e minSteering (which would be full reverse for the main DC motor) but does not move no matter what the value of driver.setPwm() is.

What could be wrong with this code?
P.S. I have already tested and controlled both at some point using servo.write() and servo.writeMicroseconds(), but from what I understand, they might not work with regular PWM duty cycle signals, which is why the Servo library works, but analogWrite will not work in this case. That’s why I want to know how the driver.setPwm() is implemented.

Hey,

this is definately going in the right direction. Regarding your code:

steering_value is an int - but the return value of your fmap() function is a float. I think you need to use a float variable to transport fmap return value to the setPwm() function. Otherwise you can only set voltages like 3.0V, 4.0V, 2.0V and this will not be precise enough.

In terms of the timings, a 50Hz 1000 - 1500 - 2000 servo will have a period time of 20000us, and 1000us = 5% of that, etc…
Hence you would use duty cycles between 95% (full reverse, 1000us pulse), 92.5% (zero point) and 90% (full forward, 2000us pulse).
Note that the control is reverse direction, with the higher duty cycle representing the lower velocity.
Why? Because I assume the servo has active-low polarity, i.e. it wants the control pulse to go from high to low. So a 90% duty cycle has a 10% low pulse…
If your servo has active-high polarity, you would just use the 5% (reverse) 7.5% (zero) and 10% (full forward) values.

Now in terms of setPwm(), with a setting of driver.voltage_power_supply = 6.0; this would mean you use control “voltages” between 6.0 * 0.9 and 6.0 * 0.95, i.e. 5.4V to 5.7V with the centre at 5.55V.
(so certainly you can’t control this using just integer voltages!)

Now you may be wondering, why deal with these voltages? Doesn’t this just make everything more complicated?

In this special case it may seem so - normally our drivers aren’t controlling RC-ESCs with receiver inputs, or servos, but rather the PWM is controlling the half-bridge switches of the ESC’s power stage directly. So the PWM normally represents a voltage quite directly.

But there is another advantage: by using a voltage as the parameter to the driver API, the other code in SimpleFOC and SimpleDC libraries can provide motor control algorithms that work on the basis of physical principals, dealing in voltages, resistances, currents and inductances.
If the output of these algorithms had to be in terms of RC-servo units we could not provide very general solutions.

Concretely, what this means for you is that if we can make this work well based on voltages, you can use SimpleDC and SimpleFOC’s other code to do closed-loop control of the motor in terms of angle radians, or velocity radians per second.

For your input control (a potentiometer?) you would read it using analogRead() and then map the integer analog value to a float voltage for the driver. Later, when you use closed loop control you would change this to map it to an angle or a velocity in rad/s for passing to the motor.move() function.

In the case of the 1PWMDriver, and the special sub-case of controlling RC-servos, we need to do the following:

  1. make the driver accept a 0-centred voltage as input to setPwm() - 0V means no motion, positive voltages mean turning in one direction and negative voltages turning in the other. Speed (or torque) are proportional to the voltage applied.
    If we make it work like this the setPwm() will be compatible with the rest of SimpleFOC.

  2. In the setPwm() we want to map the input voltage (which is 0-centred) to an output PWM duty cycle, (which is not zero-centred). In addition to the offset given by the servo zero point, we also want to scale the output by a factor. The scaling factor is given by the desired output PWM duty-cycle range, and the desired full scale voltage for the maximum duty cycle (which we could define to be the driver.voltage_power_supply). The input voltage is limited by the driver.voltage_limit, the output should be limited to the min and max duty-cycles.

  3. A complication is the fact that output duty cycle range in the positive and negative directions doesn’t have to be symmetrical - e.g. the zero point doesn’t have to be exactly between the min and the max. It could be closer to the min, for example - not uncommon for RC-cars where you generally need more range in the forward direction than the backward direction.
    This begs the question whether the scaling factor is kept the same for the forward and reverse directions, or adjusted to account for the difference in range. The remaining SimpleFOC code would generally expect the control to be symmetrical and independent of the direction.
    But you can ignore this question because in your case it is the same.

  4. Finally we should account for polarity, and allow the user to choose either polarity for the output.

Hey, I pushed some changes to the 1-PWM driver in the dev branch of the library:

I don’t have a test-setup ready to try it on, but if you can manage to use the dev-branch version of the library from GitHub you could test it out. I did not have time to add any documentation yet (I will in the future) but you should now be able to use it like this:

#define PIN_PWM 1
#define PIN_EN 5
#define THRESHOLD 0.5f

DCDriver1PWM driver = DCDriver1PWM(PIN_PWM, THRESHOLD, PIN_EN);

void setup() {
  driver.voltage_power_supply = 6.0f;
  driver.configureMicroseconds(50, 1000, 1500, 2000);
  driver.init();
}

void loop(){
  driver.setPwmMicroseconds(1900); // forwards
}

I’m guessing this will need still more work before it actually works though. The reason is that the PWM frequency on RP2040 (e.g. Pico) currently has a minimum value of 4000Hz - so you can’t set 50Hz. :frowning:
I don’t know if the servo can manage 4kHz, but I somehow doubt it, if it actually wanted 50Hz.

I will see what I can do about updating the RP2040 PWM driver to support such low frequencies.