diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index c69707a997..6cab24cbc0 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -125,7 +125,7 @@ public: k_param_battery_monitoring = 141, k_param_volt_div_ratio, k_param_curr_amp_per_volt, - k_param_input_voltage, + k_param_input_voltage, // deprecated - can be deleted k_param_pack_capacity, k_param_compass_enabled, k_param_compass, @@ -263,7 +263,6 @@ public: // 4=voltage and current AP_Float volt_div_ratio; AP_Float curr_amp_per_volt; - AP_Float input_voltage; AP_Int16 pack_capacity; // Battery pack capacity less reserve AP_Int8 failsafe_battery_enabled; // battery failsafe enabled diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 75ab7e1951..906e01f2bb 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -103,12 +103,6 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Advanced GSCALAR(curr_amp_per_volt, "AMP_PER_VOLT", CURR_AMP_PER_VOLT), - // @Param: INPUT_VOLTS - // @DisplayName: Max internal voltage of the battery voltage and current sensing pins - // @Description: Used to convert the voltage read in on the voltage and current pins for battery monitoring. Normally 5 meaning 5 volts. - // @User: Advanced - GSCALAR(input_voltage, "INPUT_VOLTS", INPUT_VOLTAGE), - // @Param: BATT_CAPACITY // @DisplayName: Battery Capacity // @Description: Battery capacity in milliamp-hours (mAh) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 27dd2687a2..19715e8f27 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -399,15 +399,6 @@ #endif - -////////////////////////////////////////////////////////////////////////////// -// INPUT_VOLTAGE -// -#ifndef INPUT_VOLTAGE - # define INPUT_VOLTAGE 5.0f -#endif - - ////////////////////////////////////////////////////////////////////////////// // MAGNETOMETER #ifndef MAGNETOMETER