From dbd9b3a9ae14b20651f85e23b81af57e6c5d2ab6 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 4 May 2021 19:10:31 +0100 Subject: [PATCH] AP_HAL_ChibiOS: ESC telemetry is orthogonal to RPM telemetry --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 49ebe65c69..b580f04354 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -1389,7 +1389,7 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us) } // according to sskaug requesting telemetry while trying to arm may interfere with the good frame calc - bool request_telemetry = (telem_request_mask & chan_mask) || group.bdshot.enabled; + bool request_telemetry = telem_request_mask & chan_mask; uint16_t packet = create_dshot_packet(value, request_telemetry, group.bdshot.enabled); if (request_telemetry) { telem_request_mask &= ~chan_mask;