DataFlash: Use battery singleton

This commit is contained in:
Michael du Breuil 2018-01-16 12:09:47 -07:00 committed by Francisco Ferreira
parent 03bf247d36
commit 725f1a2f2b
2 changed files with 10 additions and 12 deletions

View File

@ -139,7 +139,7 @@ public:
void Log_Write_Airspeed(AP_Airspeed &airspeed); void Log_Write_Airspeed(AP_Airspeed &airspeed);
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets); void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets); void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
void Log_Write_Current(const AP_BattMonitor &battery); void Log_Write_Current();
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0); void Log_Write_Compass(const Compass &compass, uint64_t time_us=0);
void Log_Write_Mode(uint8_t mode, uint8_t reason = 0); void Log_Write_Mode(uint8_t mode, uint8_t reason = 0);
@ -304,8 +304,7 @@ private:
uint64_t time_us, uint64_t time_us,
uint8_t mag_instance, uint8_t mag_instance,
enum LogMessages type); enum LogMessages type);
void Log_Write_Current_instance(const AP_BattMonitor &battery, void Log_Write_Current_instance(uint64_t time_us,
uint64_t time_us,
uint8_t battery_instance, uint8_t battery_instance,
enum LogMessages type, enum LogMessages type,
enum LogMessages celltype); enum LogMessages celltype);

View File

@ -1547,12 +1547,12 @@ void DataFlash_Class::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f
WriteBlock(&pkt, sizeof(pkt)); WriteBlock(&pkt, sizeof(pkt));
} }
void DataFlash_Class::Log_Write_Current_instance(const AP_BattMonitor &battery, void DataFlash_Class::Log_Write_Current_instance(const uint64_t time_us,
const uint64_t time_us,
const uint8_t battery_instance, const uint8_t battery_instance,
const enum LogMessages type, const enum LogMessages type,
const enum LogMessages celltype) const enum LogMessages celltype)
{ {
AP_BattMonitor &battery = AP::battery();
float temp; float temp;
bool has_temp = battery.get_temperature(temp, battery_instance); bool has_temp = battery.get_temperature(temp, battery_instance);
struct log_Current pkt = { struct log_Current pkt = {
@ -1587,20 +1587,19 @@ void DataFlash_Class::Log_Write_Current_instance(const AP_BattMonitor &battery,
} }
// Write an Current data packet // Write an Current data packet
void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery) void DataFlash_Class::Log_Write_Current()
{ {
const uint64_t time_us = AP_HAL::micros64(); const uint64_t time_us = AP_HAL::micros64();
if (battery.num_instances() >= 1) { const uint8_t num_instances = AP::battery().num_instances();
Log_Write_Current_instance(battery, if (num_instances >= 1) {
time_us, Log_Write_Current_instance(time_us,
0, 0,
LOG_CURRENT_MSG, LOG_CURRENT_MSG,
LOG_CURRENT_CELLS_MSG); LOG_CURRENT_CELLS_MSG);
} }
if (battery.num_instances() >= 2) { if (num_instances >= 2) {
Log_Write_Current_instance(battery, Log_Write_Current_instance(time_us,
time_us,
1, 1,
LOG_CURRENT2_MSG, LOG_CURRENT2_MSG,
LOG_CURRENT_CELLS2_MSG); LOG_CURRENT_CELLS2_MSG);