AP_ESC_Telem: Raise default timeout for the RPM spin check to 210ms

This copes better with 10Hz monitors, or losing a single packet
This commit is contained in:
Michael du Breuil 2023-05-25 12:17:35 -07:00 committed by Andrew Tridgell
parent 363bdc3118
commit 84104331ec

View File

@ -25,7 +25,7 @@
//#define ESC_TELEM_DEBUG
#define ESC_RPM_CHECK_TIMEOUT_US 100000UL // timeout for motor running validity
#define ESC_RPM_CHECK_TIMEOUT_US 210000UL // timeout for motor running validity
extern const AP_HAL::HAL& hal;