mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_BattMonitor: refactor Option param usage
This commit is contained in:
parent
4c6648fada
commit
61b7f6ed74
@ -506,7 +506,7 @@ float AP_BattMonitor::voltage_resting_estimate(uint8_t instance) const
|
|||||||
/// voltage - returns battery voltage in volts for GCS, may be resting voltage if option enabled
|
/// voltage - returns battery voltage in volts for GCS, may be resting voltage if option enabled
|
||||||
float AP_BattMonitor::gcs_voltage(uint8_t instance) const
|
float AP_BattMonitor::gcs_voltage(uint8_t instance) const
|
||||||
{
|
{
|
||||||
if (_params[instance].option_is_set(AP_BattMonitor_Params::Options::GCS_Resting_Voltage)) {
|
if (drivers[instance]->option_is_set(AP_BattMonitor_Params::Options::GCS_Resting_Voltage)) {
|
||||||
return voltage_resting_estimate(instance);
|
return voltage_resting_estimate(instance);
|
||||||
}
|
}
|
||||||
if (instance < _num_instances) {
|
if (instance < _num_instances) {
|
||||||
|
@ -82,6 +82,11 @@ public:
|
|||||||
// dt_us: time between samples (micro-seconds)
|
// dt_us: time between samples (micro-seconds)
|
||||||
static float calculate_mah(float amps, float dt_us) { return (float) (amps * dt_us * AUS_TO_MAH); }
|
static float calculate_mah(float amps, float dt_us) { return (float) (amps * dt_us * AUS_TO_MAH); }
|
||||||
|
|
||||||
|
// check if a option is set
|
||||||
|
bool option_is_set(const AP_BattMonitor_Params::Options option) const {
|
||||||
|
return (uint16_t(_params._options.get()) & uint16_t(option)) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AP_BattMonitor &_mon; // reference to front-end
|
AP_BattMonitor &_mon; // reference to front-end
|
||||||
AP_BattMonitor::BattMonitor_State &_state; // reference to this instances state (held in the front-end)
|
AP_BattMonitor::BattMonitor_State &_state; // reference to this instances state (held in the front-end)
|
||||||
|
@ -26,11 +26,6 @@ public:
|
|||||||
GCS_Resting_Voltage = (1U<<6), // send resistance resting voltage to GCS
|
GCS_Resting_Voltage = (1U<<6), // send resistance resting voltage to GCS
|
||||||
};
|
};
|
||||||
|
|
||||||
// check if a option is set
|
|
||||||
bool option_is_set(const Options option) const {
|
|
||||||
return (uint16_t(_options.get()) & uint16_t(option)) != 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }
|
BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }
|
||||||
|
|
||||||
AP_Int32 _pack_capacity; /// battery pack capacity less reserve in mAh
|
AP_Int32 _pack_capacity; /// battery pack capacity less reserve in mAh
|
||||||
|
@ -202,7 +202,7 @@ void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const BattInfoAuxCb &cb)
|
|||||||
|
|
||||||
void AP_BattMonitor_UAVCAN::handle_mppt_stream(const MpptStreamCb &cb)
|
void AP_BattMonitor_UAVCAN::handle_mppt_stream(const MpptStreamCb &cb)
|
||||||
{
|
{
|
||||||
const bool use_input_value = _params.option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value);
|
const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value);
|
||||||
const float voltage = use_input_value ? cb.msg->input_voltage : cb.msg->output_voltage;
|
const float voltage = use_input_value ? cb.msg->input_voltage : cb.msg->output_voltage;
|
||||||
const float current = use_input_value ? cb.msg->input_current : cb.msg->output_current;
|
const float current = use_input_value ? cb.msg->input_current : cb.msg->output_current;
|
||||||
|
|
||||||
@ -220,9 +220,9 @@ void AP_BattMonitor_UAVCAN::handle_mppt_stream(const MpptStreamCb &cb)
|
|||||||
_mppt.is_detected = true;
|
_mppt.is_detected = true;
|
||||||
|
|
||||||
// Boot/Power-up event
|
// Boot/Power-up event
|
||||||
if (_params.option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Boot)) {
|
if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Boot)) {
|
||||||
mppt_set_powered_state(true);
|
mppt_set_powered_state(true);
|
||||||
} else if (_params.option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Boot)) {
|
} else if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Boot)) {
|
||||||
mppt_set_powered_state(false);
|
mppt_set_powered_state(false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -335,10 +335,10 @@ void AP_BattMonitor_UAVCAN::mppt_check_powered_state()
|
|||||||
|
|
||||||
// check if vehicle armed state has changed
|
// check if vehicle armed state has changed
|
||||||
const bool vehicle_armed = hal.util->get_soft_armed();
|
const bool vehicle_armed = hal.util->get_soft_armed();
|
||||||
if ((!_mppt.vehicle_armed_last && vehicle_armed) && _params.option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Arm)) {
|
if ((!_mppt.vehicle_armed_last && vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Arm)) {
|
||||||
// arm event
|
// arm event
|
||||||
mppt_set_powered_state(true);
|
mppt_set_powered_state(true);
|
||||||
}else if ((_mppt.vehicle_armed_last && !vehicle_armed) && _params.option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Disarm)) {
|
} else if ((_mppt.vehicle_armed_last && !vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Disarm)) {
|
||||||
// disarm event
|
// disarm event
|
||||||
mppt_set_powered_state(false);
|
mppt_set_powered_state(false);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user