mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: minor cleanups
cleanup name to be multiplier not div ratio, and make 2 variables non-static
This commit is contained in:
parent
c64d444b5a
commit
88777beab0
|
@ -3,10 +3,6 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// static methods
|
||||
AP_HAL::AnalogSource *AP_BattMonitor::_volt_pin_analog_source;
|
||||
AP_HAL::AnalogSource *AP_BattMonitor::_curr_pin_analog_source;
|
||||
|
||||
const AP_Param::GroupInfo AP_BattMonitor::var_info[] PROGMEM = {
|
||||
// @Param: BATT_MONITOR
|
||||
// @DisplayName: Battery monitoring
|
||||
|
@ -29,11 +25,11 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] PROGMEM = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("CURR_PIN", 2, AP_BattMonitor, _curr_pin, AP_BATT_CURR_PIN),
|
||||
|
||||
// @Param: BATT_VOLTDIVIDER
|
||||
// @DisplayName: Voltage Divider
|
||||
// @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_DIVIDER). For the 3DR Power brick on APM2 or Pixhawk, this should be set to 10.1. For the PX4 using the PX4IO power supply this should be set to 1.
|
||||
// @Param: BATT_VOLT_MULT
|
||||
// @DisplayName: Voltage Multiplier
|
||||
// @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick on APM2 or Pixhawk, this should be set to 10.1. For the PX4 using the PX4IO power supply this should be set to 1.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("VOLTDIVIDER", 3, AP_BattMonitor, _volt_div_ratio, AP_BATT_VOLTDIVIDER_DEFAULT),
|
||||
AP_GROUPINFO("BATT_VOLT_MULT", 3, AP_BattMonitor, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT),
|
||||
|
||||
// @Param: BATT_APM_PERVOLT
|
||||
// @DisplayName: Apms per volt
|
||||
|
@ -90,7 +86,7 @@ AP_BattMonitor::read()
|
|||
if (_monitoring == AP_BATT_MONITOR_VOLTAGE_ONLY || _monitoring == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) {
|
||||
// this copes with changing the pin at runtime
|
||||
_volt_pin_analog_source->set_pin(_volt_pin);
|
||||
_voltage = _volt_pin_analog_source->voltage_average() * _volt_div_ratio;
|
||||
_voltage = _volt_pin_analog_source->voltage_average() * _volt_multiplier;
|
||||
}
|
||||
|
||||
// read current
|
||||
|
|
|
@ -104,7 +104,7 @@ protected:
|
|||
AP_Int8 _monitoring; /// 0=disabled, 3=voltage only, 4=voltage and current
|
||||
AP_Int8 _volt_pin;
|
||||
AP_Int8 _curr_pin;
|
||||
AP_Float _volt_div_ratio;
|
||||
AP_Float _volt_multiplier;
|
||||
AP_Float _curr_amp_per_volt;
|
||||
AP_Float _curr_amp_offset;
|
||||
AP_Int32 _pack_capacity; /// battery pack capacity less reserve
|
||||
|
@ -115,8 +115,8 @@ protected:
|
|||
float _current_total_mah; /// total current drawn since startup (Amp-hours)
|
||||
uint32_t _last_time_ms; /// time when current was last read
|
||||
|
||||
static AP_HAL::AnalogSource *_volt_pin_analog_source;
|
||||
static AP_HAL::AnalogSource *_curr_pin_analog_source;
|
||||
AP_HAL::AnalogSource *_volt_pin_analog_source;
|
||||
AP_HAL::AnalogSource *_curr_pin_analog_source;
|
||||
|
||||
};
|
||||
#endif // AP_BATTMONITOR_H
|
||||
|
|
Loading…
Reference in New Issue