AP_Motors: Battery voltage compensation maximum voltage

This commit is contained in:
murata 2021-03-05 00:40:08 +09:00 committed by Randy Mackay
parent ecf928d68b
commit 9228925bea
1 changed files with 2 additions and 2 deletions

View File

@ -52,7 +52,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
// @Range: 6 35
// @Range: 6 53
// @Units: V
// @User: Advanced
AP_GROUPINFO("BAT_VOLT_MAX", 10, AP_MotorsMulticopter, _batt_voltage_max, AP_MOTORS_BAT_VOLT_MAX_DEFAULT),
@ -60,7 +60,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
// @Range: 6 35
// @Range: 6 42
// @Units: V
// @User: Advanced
AP_GROUPINFO("BAT_VOLT_MIN", 11, AP_MotorsMulticopter, _batt_voltage_min, AP_MOTORS_BAT_VOLT_MIN_DEFAULT),