Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_BattMonitor: Do not report remaining battery percentage if battery capacity is set to 0 #13712

Merged
merged 11 commits into from
Sep 8, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1725,7 +1725,10 @@ void AP_Periph_FW::can_battery_update(void)
}

pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN;
pkt.state_of_charge_pct = battery.lib.capacity_remaining_pct(i);
uint8_t percentage = 0;
if (battery.lib.capacity_remaining_pct(percentage, i)) {
pkt.state_of_charge_pct = percentage;
}
pkt.model_instance_id = i+1;

#if !defined(HAL_PERIPH_BATTERY_SKIP_NAME)
Expand Down
9 changes: 4 additions & 5 deletions libraries/AP_BattMonitor/AP_BattMonitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -531,14 +531,13 @@ bool AP_BattMonitor::consumed_wh(float &wh, const uint8_t instance) const {
}
}

/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
bool AP_BattMonitor::capacity_remaining_pct(uint8_t &percentage, uint8_t instance) const
{
if (instance < _num_instances && drivers[instance] != nullptr) {
return drivers[instance]->capacity_remaining_pct();
} else {
return 0;
return drivers[instance]->capacity_remaining_pct(percentage);
}
return false;
}

/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_BattMonitor/AP_BattMonitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -165,9 +165,9 @@ class AP_BattMonitor
/// consumed_wh - returns total energy drawn since start-up in watt.hours
bool consumed_wh(float&wh, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;

/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
virtual uint8_t capacity_remaining_pct(uint8_t instance) const;
uint8_t capacity_remaining_pct() const { return capacity_remaining_pct(AP_BATT_PRIMARY_INSTANCE); }
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
virtual bool capacity_remaining_pct(uint8_t &percentage, uint8_t instance) const WARN_IF_UNUSED;
bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED { return capacity_remaining_pct(percentage, AP_BATT_PRIMARY_INSTANCE); }

/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
int32_t pack_capacity_mah(uint8_t instance) const;
Expand Down
15 changes: 8 additions & 7 deletions libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,16 @@ AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonit
{
}

/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
/// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const
{
float mah_remaining = _params._pack_capacity - _state.consumed_mah;
if ( _params._pack_capacity > 10 ) { // a very very small battery
Williangalvani marked this conversation as resolved.
Show resolved Hide resolved
return MIN(MAX((100 * (mah_remaining) / _params._pack_capacity), 0), UINT8_MAX);
} else {
return 0;
// we consider anything under 10 mAh as being an invalid capacity and so will be our measurement of remaining capacity
if ( _params._pack_capacity <= 10) {
return false;
}
const float mah_remaining = _params._pack_capacity - _state.consumed_mah;
percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);
return true;
}

// update battery resistance estimate
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_BattMonitor/AP_BattMonitor_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ class AP_BattMonitor_Backend
// returns true if battery monitor provides temperature
virtual bool has_temperature() const { return false; }

/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
virtual uint8_t capacity_remaining_pct() const;
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
virtual bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED;

// return true if cycle count can be provided and fills in cycles argument
virtual bool get_cycle_count(uint16_t &cycles) const { return false; }
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@ extern const AP_HAL::HAL& hal;
void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_t time_us) const
{
bool has_curr = has_current();
uint8_t percent = -1;
IGNORE_RETURN(capacity_remaining_pct(percent));
Comment on lines +10 to +11
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a change in behaviour - we're now going to log 255 rather than zero here.

I'm actually OK with that change.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, I think there's more information in 255 than a zero that could be mistaked by an empty battery.


const struct log_BAT pkt{
LOG_PACKET_HEADER_INIT(LOG_BAT_MSG),
Expand All @@ -19,7 +21,7 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_
consumed_wh : has_curr ? _state.consumed_wh : AP::logger().quiet_nanf(),
temperature : (int16_t) ( has_temperature() ? _state.temperature * 100 : 0),
resistance : _state.resistance,
rem_percent : capacity_remaining_pct(),
rem_percent : percent,
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
Expand Down
9 changes: 5 additions & 4 deletions libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,16 +146,17 @@ void AP_BattMonitor_UAVCAN::read()
_has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
}

/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t AP_BattMonitor_UAVCAN::capacity_remaining_pct() const
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
bool AP_BattMonitor_UAVCAN::capacity_remaining_pct(uint8_t &percentage) const
{
if ((uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC)) ||
_soc > 100) {
// a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then
// the user can set the option to use current integration in the backend instead.
return AP_BattMonitor_Backend::capacity_remaining_pct();
return AP_BattMonitor_Backend::capacity_remaining_pct(percentage);
}
return _soc;
percentage = _soc;
return true;
}

#endif
4 changes: 2 additions & 2 deletions libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend
/// Read the battery voltage and current. Should be called at 10hz
void read() override;

/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t capacity_remaining_pct() const override;
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
bool capacity_remaining_pct(uint8_t &percentage) const override;

bool has_temperature() const override { return _has_temperature; }

Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_Frsky_Telem/AP_Frsky_D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,9 @@ void AP_Frsky_D::send(void)
_D.last_200ms_frame = now;
send_uint16(DATA_ID_TEMP2, (uint16_t)(AP::gps().num_sats() * 10 + AP::gps().status())); // send GPS status and number of satellites as num_sats*10 + status (to fit into a uint8_t)
send_uint16(DATA_ID_TEMP1, gcs().custom_mode()); // send flight mode
send_uint16(DATA_ID_FUEL, (uint16_t)roundf(_battery.capacity_remaining_pct())); // send battery remaining
uint8_t percentage = 0;
IGNORE_RETURN(_battery.capacity_remaining_pct(percentage));
send_uint16(DATA_ID_FUEL, (uint16_t)roundf(percentage)); // send battery remaining
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this strike you as a bit weird?

We convert an integer to a float, round it, then cast it back into a uint16_t.

Similarly elsewhere.

Pre-existing, so not your problem to fix.

send_uint16(DATA_ID_VFAS, (uint16_t)roundf(_battery.voltage() * 10.0f)); // send battery voltage
float current;
if (!_battery.current_amps(current)) {
Expand Down
8 changes: 6 additions & 2 deletions libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,12 @@ void AP_Frsky_SPort::send(void)
case SENSOR_ID_FAS: // Sensor ID 2
switch (_SPort.fas_call) {
case 0:
send_sport_frame(SPORT_DATA_FRAME, FUEL_ID, (uint16_t)roundf(_battery.capacity_remaining_pct())); // send battery remaining as %
break;
{
uint8_t percentage = 0;
IGNORE_RETURN(_battery.capacity_remaining_pct(percentage));
send_sport_frame(SPORT_DATA_FRAME, FUEL_ID, (uint16_t)roundf(percentage)); // send battery remaining
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
break;
}
case 1:
send_sport_frame(SPORT_DATA_FRAME, VFAS_ID, (uint16_t)roundf(_battery.voltage() * 100.0f)); // send battery voltage in cV
break;
Expand Down
8 changes: 6 additions & 2 deletions libraries/AP_Notify/Display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -526,8 +526,12 @@ void Display::update_battery(uint8_t r)
{
char msg [DISPLAY_MESSAGE_SIZE];
AP_BattMonitor &battery = AP::battery();
uint8_t pct = battery.capacity_remaining_pct();
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT:%4.2fV %2d%% ", (double)battery.voltage(), pct) ;
uint8_t pct;
if (battery.capacity_remaining_pct(pct)) {
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT:%4.2fV %2d%% ", (double)battery.voltage(), pct) ;
} else {
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT:%4.2fV --%% ", (double)battery.voltage()) ;
}
draw_text(COLUMN(0), ROW(r), msg);
}

Expand Down
24 changes: 18 additions & 6 deletions libraries/AP_OSD/AP_OSD_Screen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1252,16 +1252,22 @@ void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP::battery();
uint8_t pct = battery.capacity_remaining_pct();
uint8_t p = (100 - pct) / 16.6;
float v = battery.voltage();
uint8_t pct;
if (!battery.capacity_remaining_pct(pct)) {
// Do not show battery percentage
backend->write(x,y, v < osd->warn_batvolt, "%2.1f%c", (double)v, SYMBOL(SYM_VOLT));
return;
}
uint8_t p = (100 - pct) / 16.6;
backend->write(x,y, v < osd->warn_batvolt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT));
}

void AP_OSD_Screen::draw_avgcellvolt(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP::battery();
uint8_t pct = battery.capacity_remaining_pct();
uint8_t pct = 0;
IGNORE_RETURN(battery.capacity_remaining_pct(pct));
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
uint8_t p = (100 - pct) / 16.6;
float v = battery.voltage();
// calculate cell count - WARNING this can be inaccurate if the LIPO/LIION battery is far from fully charged when attached and is used in this panel
Expand All @@ -1280,7 +1286,8 @@ void AP_OSD_Screen::draw_avgcellvolt(uint8_t x, uint8_t y)
void AP_OSD_Screen::draw_restvolt(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP::battery();
uint8_t pct = battery.capacity_remaining_pct();
uint8_t pct = 0;
IGNORE_RETURN(battery.capacity_remaining_pct(pct));
uint8_t p = (100 - pct) / 16.6;
float v = battery.voltage_resting_estimate();
backend->write(x,y, v < osd->warn_restvolt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT));
Expand Down Expand Up @@ -1894,9 +1901,14 @@ void AP_OSD_Screen::draw_atemp(uint8_t x, uint8_t y)
void AP_OSD_Screen::draw_bat2_vlt(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP::battery();
uint8_t pct2 = battery.capacity_remaining_pct(1);
uint8_t p2 = (100 - pct2) / 16.6;
uint8_t pct2 = 0;
float v2 = battery.voltage(1);
if (!battery.capacity_remaining_pct(pct2, 1)) {
// Do not show battery percentage
backend->write(x,y, v2 < osd->warn_bat2volt, "%2.1f%c", (double)v2, SYMBOL(SYM_VOLT));
return;
}
uint8_t p2 = (100 - pct2) / 16.6;
backend->write(x,y, v2 < osd->warn_bat2volt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p2, (double)v2, SYMBOL(SYM_VOLT));
}

Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -756,7 +756,10 @@ void AP_CRSF_Telem::calc_battery()
used_mah = 0;
}

_telem.bcast.battery.remaining = _battery.capacity_remaining_pct(0);
uint8_t percentage = 0;
IGNORE_RETURN(_battery.capacity_remaining_pct(percentage, 0));

_telem.bcast.battery.remaining = percentage;

const int32_t capacity = used_mah;
_telem.bcast.battery.capacity[0] = (capacity & 0xFF0000) >> 16;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ singleton AP_BattMonitor method voltage_resting_estimate float uint8_t 0 ud->num
singleton AP_BattMonitor method current_amps boolean float'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method consumed_mah boolean float'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method consumed_wh boolean float'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method capacity_remaining_pct uint8_t uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method capacity_remaining_pct boolean uint8_t'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method pack_capacity_mah int32_t uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method has_failsafed boolean
singleton AP_BattMonitor method overpower_detected boolean uint8_t 0 ud->num_instances()
Expand Down
15 changes: 8 additions & 7 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,9 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
} else {
consumed_wh = -1;
}
uint8_t _percentage = -1;
const int8_t percentage = battery.capacity_remaining_pct(_percentage, instance) ? _percentage : -1;

mavlink_msg_battery_status_send(chan,
instance, // id
MAV_BATTERY_FUNCTION_UNKNOWN, // function
Expand All @@ -278,7 +281,7 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
current, // current in centiampere
consumed_mah, // total consumed current in milliampere.hour
consumed_wh, // consumed energy in hJ (hecto-Joules)
battery.capacity_remaining_pct(instance),
percentage,
Williangalvani marked this conversation as resolved.
Show resolved Hide resolved
0, // time remaining, seconds (not provided)
battery.get_mavlink_charge_state(instance), // battery charge state
cell_volts_ext, // Cell 11..14 voltages
Expand Down Expand Up @@ -4639,14 +4642,13 @@ void GCS_MAVLINK::send_sys_status()

const AP_BattMonitor &battery = AP::battery();
float battery_current;
int8_t battery_remaining;
uint8_t battery_remaining = -1;

if (battery.healthy() && battery.current_amps(battery_current)) {
battery_remaining = battery.capacity_remaining_pct();
IGNORE_RETURN(battery.capacity_remaining_pct(battery_remaining));
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
} else {
battery_current = -1;
battery_remaining = -1;
Williangalvani marked this conversation as resolved.
Show resolved Hide resolved
}

uint32_t control_sensors_present;
Expand Down Expand Up @@ -5541,14 +5543,13 @@ void GCS_MAVLINK::send_high_latency() const

const AP_BattMonitor &battery = AP::battery();
float battery_current;
int8_t battery_remaining;
uint8_t battery_remaining = -1;

if (battery.healthy() && battery.current_amps(battery_current)) {
battery_remaining = battery.capacity_remaining_pct();
IGNORE_RETURN(battery.capacity_remaining_pct(battery_remaining));
battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX);
} else {
battery_current = -1;
battery_remaining = -1;
}

AP_Mission *mission = AP::mission();
Expand Down