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
  • ESC telemetry support
  • BLHeli pass-thru configuration and ESC flashing

Detailed descriptions of these features are lower down on this page.

Warning

As of April 2018 these features are currently only available with Copter-3.6, Plane-3.9, Rover-3.3 (or higher) using the ChibiOS firmware for STM32 based flight boards, and not yet in a stable release. Please join the http://gitter.im/ArduPilot/ChibiOS gitter channel for up to date information on these builds. Only try DShot on ESCs that are known to support it or you will get unpredictable results.

Where to buy

blheli32.com provides this list of BLHeli compatible ESCs. We recommend choosing one that has the telemetry wire pre-soldered (see blue wire below).

../_images/dshot-telemwire.jpg

image courtesy of hobbyking.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.

Connect all ESC’s telemetry wires to a single Telemetry RX pin on the flight board (above diagram uses Serial5).

To enable DShot:

To enable ESC telemetry:

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
  • 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.

ESC Telemetry

If using BLHeli_32, you can also enable ESC telemetry feedback, allowing you to log the following variables from each ESC in flight:

  • RPM
  • Voltage
  • current
  • temperature
  • total-current

To use ESC telemetry you need to connect a separate telemetry pin on all your ESCs back to a single UART RX pin on your flight board. 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. Support for KISS ESC Telemetry is planned.

The wires from all ESCs should all come back to a single UART RX line. The way it works is that the flight board requests telemetry from only one ESC at a time, cycling between them.

You can use any of the UARTs on your flight board for telemetry feedback. You need to enable it using the SERIALn_PROTOCOL option for the UART you are using. For example, on a Cube if you wanted to use the Serial5 UART you would set SERIAL5_PROTOCOL = 16 (where 16 is the value for “ESC Telemetry”).

You also need to set the telemetry rate in the SERVO_BLH_TRATE parameter. This rate is the rate in Hz per ESC. So if you set it to 10 then you will get 10Hz data for all ESCs.

The data is logged in the ESCn log messages in your dataflash log. This can be viewed in any ArduPilot dataflash log viewer.

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.

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, and BLHeliSuite16 for BLHeli/BLHeli_S ESCs.