A few bits about motors and ESCs

Hello,

Last Friday we received new motors : the EP4108 320KV with built-in ESC.

We’re particularly interested in those because they have a reflashable integrated BLHeli ESC. It turns out that, starting with BLHeli_S v16.5, which is an open source ESC firmware, a new protocol is supported to replace the old PWM control method : DShot. It’s a serial protocol where speed information is encoded in 16-bit frames, instead of analogically in the duty cycle of a PWM signal.

There are three generations of BLHeli firwmare : BLHeli, BLHeli_S, and BLHeli32 (wich is no longer open source), each with several versions. The integrated ESC comes with BLHeli, which does not support Dshot. We hope to be able to reflash the ESC with BLHeli_S v16.5 firmware or higher and use this protocol.

If don’t manage it, we have also ordered this standalone ESC.

We’ll then use those with the motors we previously received.

Dshot : what it is, how we found it, and why we want it

We stumbled on the DShot protocol while looking for motors that could run on a 3S LiPo battery. The motor we previously received can only run on 4S. In the meantime, this is no longer a concern because we overhauled the power transmission scheme (see this post), but we still ordered the motors because Dshot seems better than standard PWM control.

ESCs are used a lot for modelism, where analogically encoding the speed in the duty cycle of a PWM makes sense enough. But as in all analogical signals, noise can cause jitter. 

The idea of Dshot as far as I understand it is to adapt the traditional PWM signal used by ESCs to periodically send bits encoded with an either short or long duty cycle. This then becomes a digital, one-way, asynchronous, serial communication protocol.

There are several versions of DShot depending on the baud rate : DShot150 for 150 Kbits/s, Dshot300, DShot600 … The bit 0 is represented by a 3/8 duty cycle, while the bit 1 is represented by a 6/8 duty cycle. This is fairly robust to small timing variations. The DShot protocol expects 16-bit frames separated by a period at the low level. The first 11 bits contain the speed information. The next bit encodes a potential request for telemetry, and the 4 last bits are used for a checksum. On top of that, while 11 bits amount to 2048 values, the first 48 values are reserved, resulting in a 2000 step resolution for the speed command.

Testing DShot generation with ChibiOS

In order to use DShot, we not only need a DShot compatible ESC, such as an ESC with BLHeli_S, we also need to generate a DShot command to send to said ESC. In order to test our ability to do this, I wrote a test code with ChibiOS on an E407 Olimex board. 

The timer modules on the STM32F407 processors allow us to generate a hardware PWM, and to send interrupt requests to the processor on the falling and rising edges. So in order to encode the correct bits in the duty cycle width, I used the falling edge interrupt to change the duty cycle of the next PWM cycle on-the-fly, depending on whether the next bit is 0 or 1. 

Vlaya and I then analysed the output using a Saleae Logic 16 Pro unit. My test program worked well at 150 kbits/s, but reacted too slowly at 300 and 600 kbits/s, I assume because the interruptions were treated too slowly by the processor. Still, 150 kbits/s is certainly enough for our use, so it served a proof of feasibility. 

A 16 bit DShot frame of alternating zeroes and ones captured with the Saleae unit

DMA speed-up ?

I’m pretty sure there is a way to use the STM32’s DMAs in conjunction with the timer to free up the processor and achieve higher frequencies, as discussed on this forum and this forum

I’ve never used the STM32’s DMAs before, and I haven’t worked out how to do this yet. Any insight is welcome. I’m also not sure what STM32 processors include the needed DMA options.

And now ?

Next, now that we’ve received the new motors, we need to see if there’s a way to re-flash them with a firmware version that supports DShot. The motor comes with a helpfully labelled “Flash Port” exposing 6 pins, but there’s not cable for it in the box and I have no idea what to connect it to. 

Thankfully, it seems there is a way to reflash an BLHeli ESC directly through the PWM/Dshot command wire. It’s called “FC Passthrough” and is meant to allow reflashing without changing any connections, directly through the Flight Controller.

As we don’t have a Flight Controller, our tentative plan is to find and then flash a compatible FC software on an Arduino Uno, and then reflash the ESC through this Arduino using on of two applications : BLHeli Configurator, which is a chrome app, or BLHeliSuite, which only runs on Windows. We’ll work on this next week. If any of you readers has experience with modelism ESCs, your insight is again welcome 🙂

After that, we’ll try controlling the motor with the DShot signal we can generate.

PID control ?

Recently, I’ve also been thinking about how we’ll control the motor speed. We’ll likely need to use feedback control to adjust the speed and keep it from drifting. 

To that effect, we’ve planned a Hall effect sensor and an optical interruption sensor to notify us every time the motor makes a full rotation. We’ll use the sensor that gives us the most accurate information, and in the meantime we plan on having both.

There are two aspects that seem quite important at first glance : 

  • first, we want the instantaneous speed to match our command speed.
  • second, we want the number of rotations the motor has made since the speed command was given to remain close to the ideal number of rotations the motor would have made it it went exactly at the requested speed. 

A PID controller (Proportional-Integral-Derivative) seems like a good control option. In particular, the proportional term corresponds to the first aspect (instantaneous speed), and the integral term corresponds to the second aspect (number of rotations closely matching the target number of rotations). 

PID feedback scheme

Last minute update on DShot generation

Alexis just suggested to me that the DShot signal could be more easily generated via SPI : for every DShot bit we could send an 8-bit SPI frame with the first 3 bits high if we wish to send a 0, and the first 6 bits high if we which to send a 1. Or similarly, we can send 16 bits with the first 6 or 12 bits high, or 24 bits, or 32 bits, etc. Then it’s only a matter of taking the correct SPI clock frequency to achieve the desired Dshot baud rate.

This would avoid the clunky use of irqs of my current test code. I’ll try it this coming week.

What do you think ?

That’s all for now, more to follow.

Leave a Reply

Your email address will not be published. Required fields are marked *