diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 10adb3f39c..9c9edc6e02 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -33,43 +33,97 @@ AP_BattMonitor *AP_BattMonitor::_singleton; const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // 0 - 18, 20- 22 used by old parameter indexes + // Monitor 1 + // @Group: _ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[0], "_", 23, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: _ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[0], "_", 41, AP_BattMonitor, backend_analog_var_info[0]), + + // Monitor 2 + // @Group: 2_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[1], "2_", 24, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: 2_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[1], "2_", 42, AP_BattMonitor, backend_analog_var_info[1]), + + // Monitor 3 + // @Group: 3_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[2], "3_", 25, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: 3_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[2], "3_", 43, AP_BattMonitor, backend_analog_var_info[2]), + + // Monitor 4 + // @Group: 4_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[3], "4_", 26, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: 4_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[3], "4_", 44, AP_BattMonitor, backend_analog_var_info[3]), + + // Monitor 5 + // @Group: 5_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[4], "5_", 27, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: 5_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[4], "5_", 45, AP_BattMonitor, backend_analog_var_info[4]), + + // Monitor 6 + // @Group: 6_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[5], "6_", 28, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: 6_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[5], "6_", 46, AP_BattMonitor, backend_analog_var_info[5]), + + // Monitor 7 + // @Group: 7_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[6], "7_", 29, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: 7_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[6], "7_", 47, AP_BattMonitor, backend_analog_var_info[6]), + + // Monitor 8 + // @Group: 8_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[7], "8_", 30, AP_BattMonitor, AP_BattMonitor_Params), + // @Group: 8_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[7], "8_", 48, AP_BattMonitor, backend_analog_var_info[7]), + + // Monitor 9 + // @Group: 9_ // @Path: AP_BattMonitor_Params.cpp AP_SUBGROUPINFO(_params[8], "9_", 31, AP_BattMonitor, AP_BattMonitor_Params), - #if HAL_BATTMON_SMBUS_ENABLE + // @Group: 9_ + // @Path: AP_BattMonitor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[8], "9_", 49, AP_BattMonitor, backend_analog_var_info[8]), + +#if HAL_BATTMON_SMBUS_ENABLE // @Group: _ // @Path: AP_BattMonitor_SMBus.cpp AP_SUBGROUPVARPTR(drivers[0], "_", 32, AP_BattMonitor, backend_smbus_var_info[0]), @@ -110,6 +164,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { AP_GROUPEND }; +const AP_Param::GroupInfo *AP_BattMonitor::backend_analog_var_info[AP_BATT_MONITOR_MAX_INSTANCES]; + #if HAL_BATTMON_SMBUS_ENABLE const AP_Param::GroupInfo *AP_BattMonitor::backend_smbus_var_info[AP_BATT_MONITOR_MAX_INSTANCES]; #endif @@ -228,19 +284,24 @@ AP_BattMonitor::init() break; } -#if HAL_BATTMON_SMBUS_ENABLE // if the backend has some local parameters then make those available in the tree if (drivers[instance] && state[instance].var_info) { Type type = get_type(instance); - if ((type == Type::MAXELL) || (type == Type::NeoDesign) || (type == Type::Rotoye) || (type == Type::SMBus_Generic) || + if((type == Type::ANALOG_VOLTAGE_AND_CURRENT) || (type == Type::ANALOG_VOLTAGE_ONLY) || + (type == Type::FuelFlow) || (type == Type::FuelLevel_PWM)) { + backend_analog_var_info[instance] = state[instance].var_info; + AP_Param::load_object_from_eeprom(drivers[instance], backend_analog_var_info[instance]); + } +#if HAL_BATTMON_SMBUS_ENABLE + else if ((type == Type::MAXELL) || (type == Type::NeoDesign) || (type == Type::Rotoye) || (type == Type::SMBus_Generic) || (type == Type::SOLO) || (type == Type::SUI3) || (type == Type::SUI6)) { backend_smbus_var_info[instance] = state[instance].var_info; AP_Param::load_object_from_eeprom(drivers[instance], backend_smbus_var_info[instance]); } +#endif // param count could have changed AP_Param::invalidate_count(); } -#endif // call init function for each backend if (drivers[instance] != nullptr) { @@ -295,6 +356,11 @@ void AP_BattMonitor::convert_dynamic_param_groups(uint8_t instance) ap_var_type type; const char* new_name; } conversion_table[] = { + { 2, AP_PARAM_INT8, "VOLT_PIN" }, + { 3, AP_PARAM_INT8, "CURR_PIN" }, + { 4, AP_PARAM_FLOAT, "VOLT_MULT" }, + { 5, AP_PARAM_FLOAT, "AMP_PERVLT"}, + { 6, AP_PARAM_FLOAT, "AMP_OFFSET"}, { 20, AP_PARAM_INT8, "I2C_BUS" }, }; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index cbeb8d9255..41086d5d7a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -131,6 +131,7 @@ public: const struct AP_Param::GroupInfo *var_info; }; + static const struct AP_Param::GroupInfo *backend_analog_var_info[AP_BATT_MONITOR_MAX_INSTANCES]; static const struct AP_Param::GroupInfo *backend_smbus_var_info[AP_BATT_MONITOR_MAX_INSTANCES]; // Return the number of battery monitor instances diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp index 688d5b426d..06ace1525e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp @@ -1,19 +1,62 @@ #include #include #include -#include "AP_BattMonitor.h" #include "AP_BattMonitor_Analog.h" extern const AP_HAL::HAL& hal; +const AP_Param::GroupInfo AP_BattMonitor_Analog::var_info[] = { + + // @Param: VOLT_PIN + // @DisplayName: Battery Voltage sensing pin + // @Description: Sets the analog input pin that should be used for voltage monitoring. + // @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1 + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("VOLT_PIN", 1, AP_BattMonitor_Analog, _volt_pin, AP_BATT_VOLT_PIN), + + // @Param: CURR_PIN + // @DisplayName: Battery Current sensing pin + // @Description: Sets the analog input pin that should be used for current monitoring. + // @Values: -1:Disabled, 3:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 4:CubeOrange_PM2/Navigator, 14:Pixhawk2_PM2, 15:CubeOrange, 17:Durandal, 101:PX4-v1 + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("CURR_PIN", 2, AP_BattMonitor_Analog, _curr_pin, AP_BATT_CURR_PIN), + + // @Param: VOLT_MULT + // @DisplayName: Voltage Multiplier + // @Description: Used to convert the voltage of the voltage sensing pin (@PREFIX@VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1. + // @User: Advanced + AP_GROUPINFO("VOLT_MULT", 3, AP_BattMonitor_Analog, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT), + + // @Param: AMP_PERVLT + // @DisplayName: Amps per volt + // @Description: Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. + // @Units: A/V + // @User: Standard + AP_GROUPINFO("AMP_PERVLT", 4, AP_BattMonitor_Analog, _curr_amp_per_volt, AP_BATT_CURR_AMP_PERVOLT_DEFAULT), + + // @Param: AMP_OFFSET + // @DisplayName: AMP offset + // @Description: Voltage offset at zero current on current sensor + // @Units: V + // @User: Standard + AP_GROUPINFO("AMP_OFFSET", 5, AP_BattMonitor_Analog, _curr_amp_offset, 0), + + AP_GROUPEND +}; + /// Constructor AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms) : AP_BattMonitor_Backend(mon, mon_state, params) { - _volt_pin_analog_source = hal.analogin->channel(_params._volt_pin); - _curr_pin_analog_source = hal.analogin->channel(_params._curr_pin); + AP_Param::setup_object_defaults(this, var_info); + _state.var_info = var_info; + + _volt_pin_analog_source = hal.analogin->channel(_volt_pin); + _curr_pin_analog_source = hal.analogin->channel(_curr_pin); // always healthy _state.healthy = true; @@ -24,10 +67,10 @@ void AP_BattMonitor_Analog::read() { // this copes with changing the pin at runtime - _volt_pin_analog_source->set_pin(_params._volt_pin); + _volt_pin_analog_source->set_pin(_volt_pin); // get voltage - _state.voltage = _volt_pin_analog_source->voltage_average() * _params._volt_multiplier; + _state.voltage = _volt_pin_analog_source->voltage_average() * _volt_multiplier; // read current if (has_current()) { @@ -36,10 +79,10 @@ AP_BattMonitor_Analog::read() float dt = tnow - _state.last_time_micros; // this copes with changing the pin at runtime - _curr_pin_analog_source->set_pin(_params._curr_pin); + _curr_pin_analog_source->set_pin(_curr_pin); // read current - _state.current_amps = (_curr_pin_analog_source->voltage_average()-_params._curr_amp_offset)*_params._curr_amp_per_volt; + _state.current_amps = (_curr_pin_analog_source->voltage_average() - _curr_amp_offset) * _curr_amp_per_volt; // update total current drawn since startup if (_state.last_time_micros != 0 && dt < 2000000.0f) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h index a34a736345..b0d4c29ba5 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h @@ -83,18 +83,27 @@ public: AP_BattMonitor_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms); /// Read the battery voltage and current. Should be called at 10hz - void read() override; + virtual void read() override; /// returns true if battery monitor provides consumed energy info - bool has_consumed_energy() const override { return has_current(); } + virtual bool has_consumed_energy() const override { return has_current(); } /// returns true if battery monitor provides current info - bool has_current() const override; + virtual bool has_current() const override; - void init(void) override {} + virtual void init(void) override {} + + static const struct AP_Param::GroupInfo var_info[]; protected: AP_HAL::AnalogSource *_volt_pin_analog_source; AP_HAL::AnalogSource *_curr_pin_analog_source; + + // Parameters + AP_Float _volt_multiplier; /// voltage on volt pin multiplied by this to calculate battery voltage + AP_Float _curr_amp_per_volt; /// voltage on current pin multiplied by this to calculate current in amps + AP_Float _curr_amp_offset; /// offset voltage that is subtracted from current pin before conversion to amps + AP_Int8 _volt_pin; /// board pin used to measure battery voltage + AP_Int8 _curr_pin; /// board pin used to measure battery current }; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.cpp index 7259741857..fa282de175 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.cpp @@ -23,7 +23,7 @@ extern const AP_HAL::HAL& hal; AP_BattMonitor_FuelFlow::AP_BattMonitor_FuelFlow(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms) : - AP_BattMonitor_Backend(mon, mon_state, params) + AP_BattMonitor_Analog(mon, mon_state, params) { _state.voltage = 1.0; // show a fixed voltage of 1v @@ -56,7 +56,7 @@ void AP_BattMonitor_FuelFlow::irq_handler(uint8_t pin, bool pin_state, uint32_t */ void AP_BattMonitor_FuelFlow::read() { - int8_t pin = _params._curr_pin; + int8_t pin = _curr_pin; if (last_pin != pin) { // detach from last pin if (last_pin != -1) { @@ -107,7 +107,7 @@ void AP_BattMonitor_FuelFlow::read() litres = 0; litres_pec_sec = 0; } else { - litres = state.pulse_count * _params._curr_amp_per_volt * 0.001f; + litres = state.pulse_count * _curr_amp_per_volt * 0.001f; litres_pec_sec = litres / irq_dt; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.h b/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.h index 2daffc2d86..8c55567689 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelFlow.h @@ -1,9 +1,9 @@ #pragma once #include "AP_BattMonitor.h" -#include "AP_BattMonitor_Backend.h" +#include "AP_BattMonitor_Analog.h" -class AP_BattMonitor_FuelFlow : public AP_BattMonitor_Backend +class AP_BattMonitor_FuelFlow : public AP_BattMonitor_Analog { public: diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.cpp index 5f0436fb7a..9276693d79 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.cpp @@ -15,7 +15,7 @@ extern const AP_HAL::HAL& hal; /// Constructor AP_BattMonitor_FuelLevel_PWM::AP_BattMonitor_FuelLevel_PWM(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms) : - AP_BattMonitor_Backend(mon, mon_state, params) + AP_BattMonitor_Analog(mon, mon_state, params) { _state.voltage = 1.0; // show a fixed voltage of 1v @@ -28,7 +28,7 @@ AP_BattMonitor_FuelLevel_PWM::AP_BattMonitor_FuelLevel_PWM(AP_BattMonitor &mon, */ void AP_BattMonitor_FuelLevel_PWM::read() { - if (!pwm_source.set_pin(_params._curr_pin, "FuelLevelPWM")) { + if (!pwm_source.set_pin(_curr_pin, "FuelLevelPWM")) { _state.healthy = false; return; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.h b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.h index 736dbe1837..4e1965aeff 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_PWM.h @@ -1,9 +1,9 @@ #pragma once #include "AP_BattMonitor.h" -#include "AP_BattMonitor_Backend.h" +#include "AP_BattMonitor_Analog.h" -class AP_BattMonitor_FuelLevel_PWM : public AP_BattMonitor_Backend +class AP_BattMonitor_FuelLevel_PWM : public AP_BattMonitor_Analog { public: diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 7b9302c2a5..fdb77b5a05 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -1,7 +1,7 @@ #include #include #include "AP_BattMonitor_Params.h" -#include "AP_BattMonitor_Analog.h" +#include "AP_BattMonitor.h" #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) #define DEFAULT_LOW_BATTERY_VOLTAGE 10.5f @@ -17,42 +17,16 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE), + + // 2 was VOLT_PIN - // @Param: VOLT_PIN - // @DisplayName: Battery Voltage sensing pin - // @Description: Sets the analog input pin that should be used for voltage monitoring. - // @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1 - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO("VOLT_PIN", 2, AP_BattMonitor_Params, _volt_pin, AP_BATT_VOLT_PIN), + // 3 was CURR_PIN - // @Param: CURR_PIN - // @DisplayName: Battery Current sensing pin - // @Description: Sets the analog input pin that should be used for current monitoring. - // @Values: -1:Disabled, 3:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 4:CubeOrange_PM2/Navigator, 14:Pixhawk2_PM2, 15:CubeOrange, 17:Durandal, 101:PX4-v1 - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO("CURR_PIN", 3, AP_BattMonitor_Params, _curr_pin, AP_BATT_CURR_PIN), + // 4 was VOLT_MULT - // @Param: VOLT_MULT - // @DisplayName: Voltage Multiplier - // @Description: Used to convert the voltage of the voltage sensing pin (@PREFIX@VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1. - // @User: Advanced - AP_GROUPINFO("VOLT_MULT", 4, AP_BattMonitor_Params, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT), + // 5 was AMP_PERVLT - // @Param: AMP_PERVLT - // @DisplayName: Amps per volt - // @Description: Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17. - // @Units: A/V - // @User: Standard - AP_GROUPINFO("AMP_PERVLT", 5, AP_BattMonitor_Params, _curr_amp_per_volt, AP_BATT_CURR_AMP_PERVOLT_DEFAULT), - - // @Param: AMP_OFFSET - // @DisplayName: AMP offset - // @Description: Voltage offset at zero current on current sensor - // @Units: V - // @User: Standard - AP_GROUPINFO("AMP_OFFSET", 6, AP_BattMonitor_Params, _curr_amp_offset, 0), + // 6 was AMP_OFFSET // @Param: CAPACITY // @DisplayName: Battery capacity diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 7c9819ca75..1207709a73 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -23,9 +23,6 @@ public: BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); } - AP_Float _volt_multiplier; /// voltage on volt pin multiplied by this to calculate battery voltage - AP_Float _curr_amp_per_volt; /// voltage on current pin multiplied by this to calculate current in amps - AP_Float _curr_amp_offset; /// offset voltage that is subtracted from current pin before conversion to amps AP_Int32 _pack_capacity; /// battery pack capacity less reserve in mAh AP_Int32 _serial_number; /// battery serial number, automatically filled in on SMBus batteries AP_Float _low_voltage; /// voltage level used to trigger a low battery failsafe @@ -37,8 +34,6 @@ public: AP_Int32 _options; /// Options AP_Int16 _watt_max; /// max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit AP_Int8 _type; /// 0=disabled, 3=voltage only, 4=voltage and current - AP_Int8 _volt_pin; /// board pin used to measure battery voltage - AP_Int8 _curr_pin; /// board pin used to measure battery current AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe