GCS_MAVLink: Only send a single battery status per call

This commit is contained in:
Michael du Breuil 2020-06-12 16:29:00 -07:00 committed by Andrew Tridgell
parent f8acc211cf
commit 7fae084793
2 changed files with 12 additions and 5 deletions

View File

@ -222,7 +222,7 @@ public:
void send_fence_status() const;
void send_power_status(void);
void send_battery_status(const uint8_t instance) const;
bool send_battery_status() const;
bool send_battery_status();
void send_distance_sensor() const;
// send_rangefinder sends only if a downward-facing instance is
// found. Rover overrides this!
@ -844,6 +844,8 @@ private:
uint32_t last_mavlink_stats_logged;
uint8_t last_battery_status_idx;
// true if we should NOT do MAVLink on this port (usually because
// someone's doing SERIAL_CONTROL over mavlink)
bool _locked;

View File

@ -246,14 +246,19 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
}
// returns true if all battery instances were reported
bool GCS_MAVLINK::send_battery_status() const
bool GCS_MAVLINK::send_battery_status()
{
const AP_BattMonitor &battery = AP::battery();
for(uint8_t i = 0; i < battery.num_instances(); i++) {
if (battery.get_type(i) != AP_BattMonitor_Params::BattMonitor_Type::BattMonitor_TYPE_NONE) {
for(uint8_t i = 0; i < AP_BATT_MONITOR_MAX_INSTANCES; i++) {
const uint8_t battery_id = (last_battery_status_idx + 1) % AP_BATT_MONITOR_MAX_INSTANCES;
if (battery.get_type(battery_id) != AP_BattMonitor_Params::BattMonitor_Type::BattMonitor_TYPE_NONE) {
CHECK_PAYLOAD_SIZE(BATTERY_STATUS);
send_battery_status(i);
send_battery_status(battery_id);
last_battery_status_idx = battery_id;
return true;
} else {
last_battery_status_idx = battery_id;
}
}
return true;