DShot and BLHeli ESC Support

This articles describes how to setup and use three features supported by recent BLHeli ESC firmwares.

  • DShot ESC protocol support (for sending digital signals to the ESC)
  • ESC telemetry support (for receiving performance data from the ESC)
  • BLHeli pass-thru configuration and ESC flashing (for configuring the ESC)

Note

ArduPilot firmware supports the pass-through protocol with BLHeli_32 only.

Detailed descriptions of these features are lower down on this page. Dshot and telemetry ESC’s provide an advantage over traditional ESC’s for a number of reasons.

  • Provides fast, high resolution digital communication. This opens the door for more precise vehicle control and removes the need to calibrate ESC’s for different PWM ranges.
  • Telemetry ESC’s also provide monitoring of performance data that previously required additional sensors (like power modules and RPM sensors). Because of the detailed data provided by every ESC, real-time decisions can be made and logs can be analyzed for indidvidual ESC or motor failure.

Note

These features are available with Copter-3.6, Plane-3.9 and Rover-3.5 (or higher) using the ChibiOS firmware for STM32 based flight boards. Only try DShot on ESCs that are known to support it or you will get unpredictable results. Reverse thrust and virtual batteries are not yet supported in an official release.

Where to buy

A search for “BLHeli32 shopping” turns up many compatible ESCs. Look for an ESC which includes the telemetry wire connector like the HolyBro Tekko32 shown below

../_images/dshot-telemwire.png

image courtesy of holybro.com

Connecting and Configuring

../_images/dshot-pixhawk.jpg

For Pixhawk, The Cube and related boards with IO co-processors, the ESC’s ground and signal wire should be connected to the AUX OUT ports. For Pixracer and other boards with all PWM outputs coming from the main processor, the normal outputs can be used.

To enable DShot (output):

To enable ESC telemetry (feedback):

Connect all ESC’s telemetry wires to a single Telemetry RX pin on the flight board (above diagram uses Serial5). ESC telemetry is currently only available with BLHeli_32 ESCs, and a wire for the telemetry is only pre-soldered for some ESCs. If the wire isn’t pre-soldered you will need to solder it yourself. Pinouts for serial ports on The Cube can be found here. Support for KISS ESC Telemetry is planned.

  • SERIAL5_PROTOCOL = 16 (if telemetry is connected to Serial5).
  • SERVO_BLH_TRATE to 10 to enable 10hz updates and logging from the ESC.
  • SERVO_BLH_MASK to the corresponding sum for the channels you want to monitor. (channel 1 = 1, channel 9 = 256, channel 10 = 512)
  • SERVO_BLH_POLES defaults to 14 which applies to the majority of brushless motors. Adjust as required if you’re using motors with a pole count other than 14 to calculate true motor shaft RPM from ESC’s e-field RPM.

The flight board requests telemetry from only one ESC at a time, cycling between them. The following data is logged in the ESCn log messages in your dataflash log. This can be viewed in any ArduPilot dataflash log viewer.

  • RPM
  • Voltage
  • Current
  • Temperature
  • Total Current

This data can also be viewed in real-time using a ground station. If using the Mission Planner go to the Flight Data screen’s status tab and look for esc1_rpm.

../_images/dshot-realtime-esc-telem-in-mp.jpg

To configure and flash ESC’s using BLHeli, see the Pass-Through Support section bleow.

DShot Protocol

The DShot ESC protocol is a digital protocol for communication between a flight board and an ESC. The key advantages are:

  • all values sent to the ESC are protected with a 4 bit CRC
  • clock differences between the ESC and flight controller don’t affect flight
  • no need to do any ESC throttle range calibration
  • very high protocol frame frames are supported

The DShot protocol can run at several different speeds. ArduPilot supports four speeds:

  • DShot150 at 150kbaud (recommended)
  • DShot300 at 300kbaud
  • DShot600 at 600kbaud (may be needed for BLHeli_S ESC’s)
  • DShot1200 at 1200kbaud

We recommend using the lowest baud rate, DShot150, as it is the most reliable protocol (lower baudrates are less susceptible to noise on cables). Higher values will be beneficial once ArduPilot’s main loop rate is capable of speeds above 1kHz.

The protocol ArduPilot uses is controlled by setting the MOT_PWM_TYPE (or Q_M_PWM_TYPE on quadplanes) to a value from 4 to 7. The value of 4 corresponds to DShot150.

DShot sends 16 bits per frame, with bits allocated as follows:

  • 11 bits for the throttle level
  • 1 bit for telemetry request
  • 4 bits for CRC (simple XOR)

This gives a good throttle resolution, with support for asking the ESC to provide telemetry feedback. See below for more information on ESC telemetry.

We do not currently support DShot output on other vehicle types.

Note

DShot output is currently only supported on the “FMU” outputs of your flight controller. If you have a board with an IO microcontroller, with separate “main” and “auxillary” outputs, such as a Pixhawk or Cube, then you can only use DShot on the “auxillary” outputs. You will need to use the SERVOn_FUNCTION parameters to remap your motors to the auxillary outputs.

BLHeli Pass-Through Support

BLHeli pass-through support is a feature that allows you to configure and upgrade the firmware on your ESCs without having to disconnect them from your vehicle. You can plug a USB cable into your flight controller and run the BLHeliSuite software for Windows to configure your ESCs. ArduPilot firmware supports the pass-through protocol with BLHeli_32 only.

Note that you do not have to be using DShot to take advantage of BLHeli pass-through support, although it is recommended that you do.

To enable BLHeli pass-through support you need to set one of two variables:

  • SERVO_BLH_AUTO = 1 to enable automatic mapping of motors to BLHeliSuite ESC numbers. for most users this will do the right thing.
  • SERVO_BLH_MASK if you want to instead specify a specific set of servo outputs to enable. For more complex setups where you want to choose exactly which servo outputs you want to configure

Once you have enabled BLHeli support with one of the above two parameters you should reboot your flight board.

Now connect a USB cable to your flight board and use BLHeliSuite on Windows to connect. You will need to use BLHeliSuite32 for BLHeli_32 ESCs.

You need to select “BLHeli32 Bootloader (Betaflight/Cleanflight)” from the interfaces menu

../_images/blhelisuite32.jpg