From fff143d83e13830c3d44ad4d99a2707a88e1167d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 3 Apr 2018 07:10:38 +1000 Subject: [PATCH] AP_BLHeli: default protocol timeout to 0 this gives best compatibility with BLHeliSuite --- libraries/AP_BLHeli/AP_BLHeli.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index 1a23836e56..0179bbafa8 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -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