Browse Source

AP_BattMonitor: get Mavlink charge state

zr-v5.1
Josh Henderson 4 years ago committed by Andrew Tridgell
parent
commit
80a17cb97f
  1. 25
      libraries/AP_BattMonitor/AP_BattMonitor.cpp
  2. 3
      libraries/AP_BattMonitor/AP_BattMonitor.h

25
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -588,6 +588,31 @@ bool AP_BattMonitor::reset_remaining_mask(uint16_t battery_mask, float percentag @@ -588,6 +588,31 @@ bool AP_BattMonitor::reset_remaining_mask(uint16_t battery_mask, float percentag
return ret;
}
// Returns the mavlink charge state. The following mavlink charge states are not used
// MAV_BATTERY_CHARGE_STATE_EMERGENCY , MAV_BATTERY_CHARGE_STATE_FAILED
// MAV_BATTERY_CHARGE_STATE_UNHEALTHY, MAV_BATTERY_CHARGE_STATE_CHARGING
MAV_BATTERY_CHARGE_STATE AP_BattMonitor::get_mavlink_charge_state(const uint8_t instance) const
{
if (instance >= _num_instances) {
return MAV_BATTERY_CHARGE_STATE_UNDEFINED;
}
switch (state[instance].failsafe) {
case Failsafe::None:
return MAV_BATTERY_CHARGE_STATE_OK;
case Failsafe::Low:
return MAV_BATTERY_CHARGE_STATE_LOW;
case Failsafe::Critical:
return MAV_BATTERY_CHARGE_STATE_CRITICAL;
}
// Should not reach this
return MAV_BATTERY_CHARGE_STATE_UNDEFINED;
}
namespace AP {
AP_BattMonitor &battery()

3
libraries/AP_BattMonitor/AP_BattMonitor.h

@ -214,6 +214,9 @@ public: @@ -214,6 +214,9 @@ public:
bool reset_remaining_mask(uint16_t battery_mask, float percentage);
bool reset_remaining(uint8_t instance, float percentage) { return reset_remaining_mask(1U<<instance, percentage);}
// Returns mavlink charge state
MAV_BATTERY_CHARGE_STATE get_mavlink_charge_state(const uint8_t instance) const;
static const struct AP_Param::GroupInfo var_info[];
protected:

Loading…
Cancel
Save