mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Fix battery failsafe parameter conversion
This commit is contained in:
parent
5740ea55e8
commit
4540109513
@ -649,8 +649,8 @@ ParametersG2::ParametersG2()
|
||||
}
|
||||
|
||||
const AP_Param::ConversionInfo conversion_table[] = {
|
||||
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_FS_LOW_VOLT" },
|
||||
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_FS_LOW_MAH" },
|
||||
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" },
|
||||
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" },
|
||||
{ Parameters::k_param_failsafe_battery_enabled, 0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user