AP_Motors: Use the same limits described in the wiki

According to Leonard Hall's tuning instructions at:
https://ardupilot.org/copter/docs/tuning-process-instructions.html
Fix a typo
This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2021-05-06 12:20:36 +02:00 committed by Andrew Tridgell
parent 393ac386cc
commit 2393097417
1 changed files with 3 additions and 3 deletions

View File

@ -51,7 +51,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @Param: BAT_VOLT_MAX
// @DisplayName: Battery voltage compensation maximum voltage
// @Description: Battery voltage compensation maximum voltage (voltage above this will have no additional scaling effect on thrust). Recommend 4.4 * cell count, 0 = Disabled
// @Description: Battery voltage compensation maximum voltage (voltage above this will have no additional scaling effect on thrust). Recommend 4.2 * cell count, 0 = Disabled
// @Range: 6 53
// @Units: V
// @User: Advanced
@ -59,7 +59,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @Param: BAT_VOLT_MIN
// @DisplayName: Battery voltage compensation minimum voltage
// @Description: Battery voltage compensation minimum voltage (voltage below this will have no additional scaling effect on thrust). Recommend 3.5 * cell count, 0 = Disabled
// @Description: Battery voltage compensation minimum voltage (voltage below this will have no additional scaling effect on thrust). Recommend 3.3 * cell count, 0 = Disabled
// @Range: 6 42
// @Units: V
// @User: Advanced
@ -84,7 +84,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL),
// @Param: PWM_MIN
// @DisplayName: PWM output miniumum
// @DisplayName: PWM output minimum
// @Description: This sets the min PWM output value in microseconds that will ever be output to the motors, 0 = use input RC3_MIN
// @Units: PWM
// @Range: 0 2000