Browse Source

AP_BLHeli: default protocol timeout to 0

this gives best compatibility with BLHeliSuite
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
fff143d83e
  1. 2
      libraries/AP_BLHeli/AP_BLHeli.cpp

2
libraries/AP_BLHeli/AP_BLHeli.cpp

@ -70,7 +70,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { @@ -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

Loading…
Cancel
Save