AP_BLHeli: default protocol timeout to 0

this gives best compatibility with BLHeliSuite
This commit is contained in:
Andrew Tridgell 2018-04-03 07:10:38 +10:00
parent 2c6e6e3b13
commit fff143d83e

View File

@ -70,7 +70,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
// @Units: s
// @Range: 0 300
// @User: Standard
AP_GROUPINFO("TMOUT", 4, AP_BLHeli, timeout_sec, 60),
AP_GROUPINFO("TMOUT", 4, AP_BLHeli, timeout_sec, 0),
// @Param: TRATE
// @DisplayName: BLHeli telemetry rate