GCS_MAVLink: Reduce scoping on AP_BattMonitor include

This commit is contained in:
Michael du Breuil 2019-06-13 15:57:04 -07:00 committed by Andrew Tridgell
parent eed710db5f
commit 8c00102259
3 changed files with 7 additions and 6 deletions

View File

@ -1,5 +1,6 @@
#include "GCS.h" #include "GCS.h"
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;

View File

@ -7,7 +7,6 @@
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include "GCS_MAVLink.h" #include "GCS_MAVLink.h"
#include <AP_Mission/AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <stdint.h> #include <stdint.h>
#include "MAVLink_routing.h" #include "MAVLink_routing.h"
#include <AP_SerialManager/AP_SerialManager.h> #include <AP_SerialManager/AP_SerialManager.h>
@ -397,8 +396,7 @@ public:
void send_meminfo(void); void send_meminfo(void);
void send_fence_status() const; void send_fence_status() const;
void send_power_status(void); void send_power_status(void);
void send_battery_status(const AP_BattMonitor &battery, void send_battery_status(const uint8_t instance) const;
const uint8_t instance) const;
bool send_battery_status() const; bool send_battery_status() const;
void send_distance_sensor() const; void send_distance_sensor() const;
// send_rangefinder sends only if a downward-facing instance is // send_rangefinder sends only if a downward-facing instance is

View File

@ -57,6 +57,8 @@
#include <AP_ToshibaCAN/AP_ToshibaCAN.h> #include <AP_ToshibaCAN/AP_ToshibaCAN.h>
#endif #endif
#include <AP_BattMonitor/AP_BattMonitor.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms; 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()); hal.analogin->power_status_flags());
} }
void GCS_MAVLINK::send_battery_status(const AP_BattMonitor &battery, void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
const uint8_t instance) const
{ {
// catch the battery backend not supporting the required number of cells // 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), static_assert(sizeof(AP_BattMonitor::cells) >= (sizeof(uint16_t) * MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN),
"Not enough battery cells for the MAVLink message"); "Not enough battery cells for the MAVLink message");
const AP_BattMonitor &battery = AP::battery();
float temp; float temp;
bool got_temperature = battery.get_temperature(temp, instance); 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++) { for(uint8_t i = 0; i < battery.num_instances(); i++) {
if (battery.get_type(i) != AP_BattMonitor_Params::BattMonitor_Type::BattMonitor_TYPE_NONE) { if (battery.get_type(i) != AP_BattMonitor_Params::BattMonitor_Type::BattMonitor_TYPE_NONE) {
CHECK_PAYLOAD_SIZE(BATTERY_STATUS); CHECK_PAYLOAD_SIZE(BATTERY_STATUS);
send_battery_status(battery, i); send_battery_status(i);
} }
} }
return true; return true;