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

GCS_MAVLink: Only send a single battery status per call #14592

Merged
merged 1 commit into from
Jun 22, 2020
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
4 changes: 3 additions & 1 deletion libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ class GCS_MAVLINK
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!
Expand Down Expand Up @@ -844,6 +844,8 @@ class GCS_MAVLINK

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;
Expand Down
13 changes: 9 additions & 4 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down