From 8c001022598c49fda1910a6bc2c96a41eeda5a0b Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 13 Jun 2019 15:57:04 -0700 Subject: [PATCH] GCS_MAVLink: Reduce scoping on AP_BattMonitor include --- libraries/GCS_MAVLink/GCS.cpp | 1 + libraries/GCS_MAVLink/GCS.h | 4 +--- libraries/GCS_MAVLink/GCS_Common.cpp | 8 +++++--- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index 8ce292fb0b..9d1c9a0546 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -1,5 +1,6 @@ #include "GCS.h" #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 7217a4eee2..43c2c536bd 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -7,7 +7,6 @@ #include #include "GCS_MAVLink.h" #include -#include #include #include "MAVLink_routing.h" #include @@ -397,8 +396,7 @@ public: void send_meminfo(void); void send_fence_status() const; void send_power_status(void); - void send_battery_status(const AP_BattMonitor &battery, - const uint8_t instance) const; + void send_battery_status(const uint8_t instance) const; bool send_battery_status() const; void send_distance_sensor() const; // send_rangefinder sends only if a downward-facing instance is diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index e25893ee44..aa4dea90ee 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -57,6 +57,8 @@ #include #endif +#include + extern const AP_HAL::HAL& hal; uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms; @@ -267,13 +269,13 @@ void GCS_MAVLINK::send_power_status(void) hal.analogin->power_status_flags()); } -void GCS_MAVLINK::send_battery_status(const AP_BattMonitor &battery, - const uint8_t instance) const +void GCS_MAVLINK::send_battery_status(const uint8_t instance) const { // catch the battery backend not supporting the required number of cells static_assert(sizeof(AP_BattMonitor::cells) >= (sizeof(uint16_t) * MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN), "Not enough battery cells for the MAVLink message"); + const AP_BattMonitor &battery = AP::battery(); float temp; bool got_temperature = battery.get_temperature(temp, instance); @@ -317,7 +319,7 @@ bool GCS_MAVLINK::send_battery_status() const for(uint8_t i = 0; i < battery.num_instances(); i++) { if (battery.get_type(i) != AP_BattMonitor_Params::BattMonitor_Type::BattMonitor_TYPE_NONE) { CHECK_PAYLOAD_SIZE(BATTERY_STATUS); - send_battery_status(battery, i); + send_battery_status(i); } } return true;