Copter: Fix battery failsafe param conversion

This commit is contained in:
Michael du Breuil 2018-11-05 14:43:58 -07:00 committed by Randy Mackay
parent b579a36d8d
commit 547c9f0bf4
1 changed files with 3 additions and 3 deletions

View File

@ -1043,9 +1043,9 @@ const AP_Param::ConversionInfo conversion_table[] = {
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" }, { Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
{ Parameters::k_param_arming_check_old, 0, AP_PARAM_INT8, "ARMING_CHECK" }, { Parameters::k_param_arming_check_old, 0, AP_PARAM_INT8, "ARMING_CHECK" },
// battery // battery
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_INT8, "BATT_FS_LOW_VOLT" }, { Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" },
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_INT8, "BATT_FS_LOW_MAH" }, { 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" }, { Parameters::k_param_failsafe_battery_enabled,0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },
}; };
void Copter::load_parameters(void) void Copter::load_parameters(void)