Copter: Matches the minimum value of failsafe_throttle_value to the operation

This commit is contained in:
murata 2020-09-21 12:50:24 +09:00 committed by Randy Mackay
parent 44fb4b5e67
commit 1c4cfac851
1 changed files with 1 additions and 1 deletions

View File

@ -244,7 +244,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Param: FS_THR_VALUE
// @DisplayName: Throttle Failsafe Value
// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers
// @Range: 925 1100
// @Range: 910 1100
// @Units: PWM
// @Increment: 1
// @User: Standard