DShot ESCs

../_images/hobbywing-esc.jpg

DShot is a digital ESC protocol which allows fast, high resolution digital communication which may improve vehicle control which is especially useful in multirotor and quadplane applications. Other advantages include

  • Values sent to the ESC are checksum-protected

  • Clock differences between the ESC and autopilot don’t affect flight performance

  • ESC calibration is not required

DShot is the underlying ESC control protocol used by BLHeli/AM32 ESCs. Many BLHeli/AM32 ESC versions offer even more features such as ESC configuration, ESC telemetry, LED control and/or Bi-directional dshot. If choosing a DShot enabled ESC we recommend using one that also supports BLHeli32, AM32, or BLHeli_S.

Note

Only try DShot on ESCs that are known to support it or you will get unpredictable results.

Note

Recently there is a growing number of proprietary and non-proprietary 16 / 32 bit ESCs with firmware that support DShot and other digital ESC protocols, but not BLHeli32/AM32 specific features like passthrough and telemetry. See your ESC’s manual for further detail on supported features.

Note

most DShot ESCs normally will also operate as normal PWM ESCs.

Connecting the ESCs

For firmware versions prior to 4.5, autopilots with an IOMCU co-processor (e.g. Pixhawk, CubeOrange,etc.) the DShot ESCs should be connected to the AUX outputs and not the MAIN outputs of the IOMCU co-processor. In firmware versions 4.5 or later, the BRD_IO_DSHOT parameter may be set to load Dshot compatible IOMCU firmware on the next bootup for some autopilots using F103 IOMCUs. If this parameter is not present, then the autopilot does not have DShot capability on its IOMCU outoputs. See the IOMCU Dshot Limitations section for limitations and more information.

On CubeOrange DShot works on all channels. AUX1 cannot be used for Bi-Directional DShot meaning only AUX2 to AUX6 can be used for Bi_directional DShot. (see issue).

For other boards without a separate IOMCU coprocessor, any servo/motor outputs can be used for DShot.

Please see the Mixing ESC Protocols section below for more details on limitations

BiDirectional DShot

Some boards

Select the DShot baud rate

Set MOT_PWM_TYPE for the desired baud rate and reboot the autopilot

  • DShot150 at 150kbaud (recommended for larger aircraft with long signal lead runs)

  • DShot300 at 300kbaud

  • DShot600 at 600kbaud (recommended for most vehicles)

  • DShot1200 at 1200kbaud

For larger aircraft with longer cable runs using DShot ESC protocol, we recommend using the lowest baud rate, DShot150, as it is the most reliable protocol (lower baudrates are less susceptible to noise on cables).

For smaller craft, DShot600 is by far the most widely used and can therefore be a more suitable choice simply because of the amount of testing that it has had, rather than the newer DShot1200 protocol.

Higher rates (e.g. DShot600 and DShot1200) are more susceptible to noise but have the advantage that they tie up the allocated DMA channel for less time which can be beneficial on autopilots with a lot of DMA sharing.

If Bi-directional DShot will be used, DShot300 and DShot600 are preferred, because this feature requires a longer pulse width as it has to wait for the response from the ESC before it can send another pulse. Bi-directional DShot does not share DMA channels and so there is no impact on other peripherals. Bi-directional DShot is only supported on BLHeli32/AM32 ESCs

Configure the Servo Functions

As mentioned above, if using an autopilot with an IOMCU (e.g. Pixhawk, CubeOrange,etc.) the ESCs should be connected to the AUX outputs instead of the default MAIN outputs. This in turn means that the corresponding SERVOx_FUNCTION parameters must be updated so the autopilot knows which output is connected to the ESCs/motors. This can be most easily done using Mission Planner’s “Servo Output” page

../_images/dshot-setup-mp-servooutput.png

Note

When an output is configured for DShot, the SERVOx_MIN/MAX/TRIM parameters for that output will always be ignored since DShot does not use these parameters. The trim value used will be 1500 if it’s a reversible output, or 1000 if normal output setup in DShot, and the output range always be 1000-2000. No ESC calibration step is required.

Note

All mask-based configuration can only be changed at a PWM group level, please consult the documentation for your autopilot to ascertain which outputs are on different groups. See Mixing ESC Protocols section below.

Warning

Be sure your ESC can support the configuration you select for it. Damage can occur otherwise. This includes frame rates discussed below. Also be careful when switching between digital and analogue output types without re-calibrating ESCs as this can lead to uncommanded motor output.

Check the RC Banner

Reboot the autopilot and check the “RC banner” to confirm the output channels are setup as expected (this banner appears whenever parameters are downloaded)

../_images/dshot-setup-mp-rcbanner.png

Additional Configuration

DShot Update Rates

The frequency at which DShot pulses are sent can be configured through SERVO_DSHOT_RATE. By default ArduPilot will output a DShot data pulse every time a new IMU sample is ready and at a fixed 1Khz interval. On a copter with the standard 400Hz scheduler loop rate this works out at about 1.4Khz. However, the output is quite irregular - in order to get more regular output SERVO_DSHOT_RATE can be configured to send pulses at multiples of the scheduler loop rate. Thus if set to 2 the pulses will be sent at 800Hz, set to 3 at 1.2Khz and so on. The difference being very, very even output which can benefit copters needing tighter motor control (for instance smaller racers). It is not recommended to send pulses at less than 1Khz due to reports of BLHeli32 occasionally missing frames on some autopilots, similarly sending at higher rates can result in increased reliability and faster recovery from missed pulses where needed at the cost of some CPU. Very high rates can only be used for faster DShot speeds since otherwise pulses might overlap - for instance the fastest rate that DShot150 can theoretically support is 4Khz.

DShot Commands

On certain ESCs DShot commands are supported. These allow functions such as ESC LEDs, beeps and motor direction to be manipulated by the autopilot. In order to use DShot commands:

  • set SERVO_DSHOT_ESC should be set to the type of DShot ESCs being used. This is required especially if Bi-Directional DShot telemetry or Extended Telemetry is being used.

  • set NTF_LED_TYPES’s “DShot” checkbox to enable controlling the ESCs LEDs

  • set NTF_BUZZ_TYPES’s “DShot” checkbox to enable usingthe motors as buzzers

The current commands supported are:

Warning

Currently, ArduPilot supports the command set (SERVO_DSHOT_ESC =1) that is commonly used, however, others are appearing and may not be compatible, resulting in undefined operation. Use caution (remove blades!) until correct operation using type=1 is verified for your ESC

Reversible DShot ESCs

Reversible DShot (aka 3D mode) allows the motor to be spun in either direction which is important for Rover, Boats and Planes with reverse thrust.

Currently, only BLHeli32, AM32, and BLHeli_S capable reversible DShot ESCs are supported. In order to use one, the output which drives it must be designated with the appropriate bit in the SERVO_BLH_3DMASK bitmask parameter. This will map the outputs 1000-1500-2000 values to the correct digital values for the ESC to provide FullReverse-Idle-FullForward range operation, respectively.

If DShot commands have been enabled then ArduPilot will automatically configure the ESCs to reversible mode (3D mode) at startup, according to the SERVO_BLH_3DMASK. Enabling DShot commands will allow the other DShot commands to be sent to any other ESC configured as DShot by the DShot mask parameters discussed in DShot setup instructions.

Otherwise, you must manually configure the ESCs’ “Motor Direction” to “Bidirectional 3D” as shown below.

../_images/blheli-reversible-dshot.png

Note

Currently, ArduPilot only supports the use of reversible ESCs for Plane and Rover, not Copter.

Mixing ESC Protocols

While all the servo/motor outputs of an ArduPilot autopilot are capable of Normal PWM operation at 50Hz and higher frame rates, not all are capable of other ESC protocol configurations. And, usually, these configurations must apply to pre-designated groups of outputs, even if they are not all driving an ESC. So the following cautions apply:

  1. The 8 “MAIN” outputs of autopilots using an IOMCU (like PixHawk and Cube), cannot be used for DShot. On these autopilots, only the additional “AUX” outputs support DShot. If you attempt to set a “MAIN” output to DShot, then normal PWM output will occur, even though it has been set to a DShot protocol.

  2. For Pixracer and other boards without a separate IOMCU coprocessor, all servo/motor outputs can be used.

  3. Groups of outputs sharing a common timer, MUST have the same advanced configuration. Usually, these are specified in the autopilot’s hardware description linked from the Choosing an Autopilot page. For example, if an output is configured for DShot in a group, then you cannot use another output in that group for Normal PWM ESC or normal PWM servo operation.

Note

Everytime the autopilot initializes, it sends a message to the ground control station, showing which outputs are PWM/Oneshot/or DShot. The remaining higher numbered outputs are assigned as GPIOs.

../_images/RCOutbanner.jpg

IOMCU DShot Limitations

If the DShot enabled IOMCU firmware has been loaded (See Connecting ESCs section above), there are certain limitations:

  • PPM can no longer be detected on the RCin pin

  • The “MAIN” outputs can support PWM as well as normal DShot, but the “grouping” of like protocols to the timer groups are:
    • MAIN 1,2 Group1

    • MAIN 3,4 Group2

    • MAIN 5-8 Group3

All normal setup instructions for DShot outputs apply also.