ESC Telemetry¶
If the ESC has this capability, it allows monitoring and logging of performance data that previously required additional sensors (like power modules and RPM sensors). The detailed data provided by every ESC allows real-time decisions and individual ESC or motor performance tuning and failure analysis. Note that a given ESC may or may not have a specific sensor type’s data transmitted via telemetry. It is common for 4 in 1 escs to provide voltage and current sensors but not transmit the data via telemetry, but rather by direct connection to the autopilot. Check the ESC data sheet and connection information for details.
Telemetry data may be conveyed to the autopilot either by a separate wire connection to an autopilot’s UART RX pin or across the signal wire used to convey motor speed information (Bi-Directional DShot) or CAN messages for CAN based ESCs. For non-CAN ESCs, this capability is available primarily in selected BLHeli ESCs running stock or BlueJay firmware. But it is possible for an ESC not to implement the BLHeli firmware and still provide this capability. Currenly, ArduPilot only supports this for BLHeli/BlueJay telemetry compatible ESCs.
ESC telemetry of motor RPM is especially useful for controlling the center frequency of harmonic notch filters to control noise. See ESC Telemetry Based Harmonic Notch Setup for more information.
Note
ArduPilot does not currently support the polling of the ESCs for telemetry data via throttle idle messages over the signal line in non DShot protocols.
Connecting the ESCs Telemetry wire¶
Connect all ESC telemetry wires to a single serial port’s RX pin on the autopilot (above diagram uses Serial5 as an example). A pin or wire for ESC telemetry is pre-soldered on most BLHeli32 ESCs. If the wire isn’t pre-soldered you will need to solder it yourself. CubePilot serial port pinsouts can be found here.
Set the following parameters to enable BLHeli32/AM32 telemetry feedback to the autopilot’s serial port:
SERIALx_PROTOCOL 16 (= ESC telemetry) where “x” is the autopilot serial port number connected to the ESCs telemetry wire. The mapping between serial port numbering and UART physical ports for you autopilot should be documented in its description page linked here.
SERVO_BLH_TRATE defaults to 10 and normally does not need to be changed. this enables telemetry at a 10Hz update rate from the ESC. If using the harmonic notch feature this can be raised to 100.
SERVO_BLH_POLES defaults to 14 which applies to the majority of brushless motors and normally does not need to be changed. 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.
Note
using the RPM value reported using single wire telemetry for the center frequency adjustment of the harmonic notch feature works well, but the responsiveness is slower than using telemetry provided by bi-directional DShot. See next section.
Bi-directional DShot¶
Newer versions of AM32, BLHeli32 (32.7 and higher), and BLHeli_S (16.73 and higher) support returning motor RPM values over the DShot signal line. Supporting bi-directional DShot requires exclusive use of one or more DMA channels and thus not all autopilots support it. Versions that support bi-directional DShot have this stated in their wiki pages, see Choosing an Autopilot for your autopilot.
Some autopilots with IOMCUs can not only support Dshot on their “Main” outputs (see DShot ESCs for setup and more information), but also bi-directional DShot on their first four outputs. Currently, this is limited only to Pixhawk6X/C autopilots.
Setup¶
First ensure that you have an appropriate version of BLHeli32 or BLHeli_S installed on your ESCs. The majority of ESCs do not come pre-installed with these versions. The official 32.7 version of BLHeli32 supports bi-directional DShot. Official versions of BLHeli_S do not support bi-directional DShot, you will need to either buy a version from BLHeli_S JESC or use BLHeli_S BlueJay . If you try and enable bi-directional DShot with the wrong firmware version then unpredictable motor operation can occur. ESC RPM telemetry is especially useful for controlling the center frequencies of harmonic notch noise filters, see ESC Telemetry Based Harmonic Notch Setup
Set the following parameters to enable BLHeli32 and BLHeli_S bi-directional DShot:
SERVO_BLH_BDMASK: a bitmap used to enable BLHeli32, AM32, or BLHeli_S bi-directional DShot support. On autopilots without IOMCU this would normally be set to 15 to indicate four active channels. On autopilots with an IOMCU this can be set to 3840 to indicate four active AUX channels (bi-directional DShot will only work on the AUX outputs).
SERVO_BLH_POLES defaults to 14 which applies to the majority of brushless motors and normally does not need to be changed. 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 (small motors might have 12 poles).
SERVO_DSHOT_ESC must be set to the type of Dshot ESC you are using.
ESC Telemetry Logging and Reporting¶
The autopilot requests status information from one ESC at a time, cycling between them. This information is logged to the onboard log’s ESCn messages and can be viewed in any ArduPilot compatible log viewer.
RPM
Voltage
Current
Temperature
Total Current
The RCOU messages are also written to the onboard logs which hold the requested output level sent to the ESCs expressed as a number from 1000 (meaning stopped) to 2000 (meaning full output).
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.
Note
Sending BLHeli32 telemetry data to the GCS requires the telemetry connection use MAVLink2. ArduPilot uses MAVLink2 by default on the USB port but if another port is used it may be necessary to set the SERIALx_PROTOCOL parameter to 2 (where “x” is the serial port number used for the telemetry connection).
In addition, some telemetry values can be displayed on the integrated on-board OSD, if your autopilot has one.
Newer firmware versions (such as BlHeli32 starting at version 32.10, and Bluejay starting at version 0.19) report some of the information above also via bi-directional DShot, using a protocol extension known as Extended DShot Telemetry. The version 2 of this protocol, EDTv2, also specifies the following information that can be reported by an ESC:
Commutation stress
Error events (such as propeller stalls)
Warning events (such as desyncs)
Alert events (such as demagnetization events)
If an ESC connected via bidirectional DShot supports this extension, this information is automatically sent to the flight controller, where it is logged as EDT2 messages. This information is typically sent on a best-efforts basis, and is intended mainly for post-flight analysis.
Use as Battery Monitor¶
By setting a battery monitor instance to BLHeli32 ESC type (for example BATT2_MONITOR = 9), all connected BLHeli32 ESCs with connected telemetry wiring to the configured autopilot serial port, will be aggregated as a single source. Normally all the ESC’s reported voltages and temperatures reported will be averaged, their currents totaled, and the consumed current accumulated. However, an individual monitor may select which ESC’s values will be used, instead of all, by setting (Battery Monitor 3 will used for example here) BATT3_ESC_MASK bits for the indexes of which ESC’s values will be used. Default is to use all ESCs setup to report power telemetry.