diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 72333c44df..cd8e6d2916 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -181,7 +181,7 @@ public: k_param_radio_tuning_high, k_param_radio_tuning_low, k_param_rc_speed = 192, - k_param_battery_fs_enabled, // 193 + k_param_failsafe_battery_enabled, // 193 // // 200: flight modes @@ -255,7 +255,7 @@ public: AP_Float curr_amp_per_volt; AP_Float input_voltage; AP_Int16 pack_capacity; // Battery pack capacity less reserve - AP_Int8 battery_fs_enabled; // battery failsafe enabled + AP_Int8 failsafe_battery_enabled; // battery failsafe enabled AP_Int8 compass_enabled; AP_Int8 optflow_enabled; diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 9f83814abf..1bcc1bbeea 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -79,12 +79,12 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Standard GSCALAR(battery_monitoring, "BATT_MONITOR", DISABLED), - // @Param: BATT_FAILSAFE + // @Param: FS_BATT_ENABLE // @DisplayName: Battery Failsafe Enable // @Description: Controls whether failsafe will be invoked when battery voltage or current runs low // @Values: 0:Disabled,1:Enabled // @User: Standard - GSCALAR(battery_fs_enabled, "BATT_FAILSAFE", BATTERY_FAILSAFE), + GSCALAR(failsafe_battery_enabled, "FS_BATT_ENABLE", FS_BATTERY), // @Param: VOLT_DIVIDER // @DisplayName: Voltage Divider diff --git a/ArduCopter/config.h b/ArduCopter/config.h index e9b633f85c..c47852f41e 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -318,8 +318,8 @@ #endif // Battery failsafe -#ifndef BATTERY_FAILSAFE - # define BATTERY_FAILSAFE DISABLED +#ifndef FS_BATTERY + # define FS_BATTERY DISABLED #endif diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde index 4e069eb242..c438a19d41 100644 --- a/ArduCopter/events.pde +++ b/ArduCopter/events.pde @@ -65,7 +65,7 @@ static void low_battery_event(void) gcs_send_text_P(SEVERITY_LOW,PSTR("Low Battery!")); // failsafe check - if (g.battery_fs_enabled && !ap.low_battery && motors.armed()) { + if (g.failsafe_battery_enabled && !ap.low_battery && motors.armed()) { switch(control_mode) { case STABILIZE: case ACRO: