DataFlash: Use battery singleton
This commit is contained in:
parent
03bf247d36
commit
725f1a2f2b
@ -139,7 +139,7 @@ public:
|
||||
void Log_Write_Airspeed(AP_Airspeed &airspeed);
|
||||
void Log_Write_Attitude(AP_AHRS &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_Mode(uint8_t mode, uint8_t reason = 0);
|
||||
|
||||
@ -304,8 +304,7 @@ private:
|
||||
uint64_t time_us,
|
||||
uint8_t mag_instance,
|
||||
enum LogMessages type);
|
||||
void Log_Write_Current_instance(const AP_BattMonitor &battery,
|
||||
uint64_t time_us,
|
||||
void Log_Write_Current_instance(uint64_t time_us,
|
||||
uint8_t battery_instance,
|
||||
enum LogMessages type,
|
||||
enum LogMessages celltype);
|
||||
|
@ -1547,12 +1547,12 @@ void DataFlash_Class::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void DataFlash_Class::Log_Write_Current_instance(const AP_BattMonitor &battery,
|
||||
const uint64_t time_us,
|
||||
void DataFlash_Class::Log_Write_Current_instance(const uint64_t time_us,
|
||||
const uint8_t battery_instance,
|
||||
const enum LogMessages type,
|
||||
const enum LogMessages celltype)
|
||||
{
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
float temp;
|
||||
bool has_temp = battery.get_temperature(temp, battery_instance);
|
||||
struct log_Current pkt = {
|
||||
@ -1587,20 +1587,19 @@ void DataFlash_Class::Log_Write_Current_instance(const AP_BattMonitor &battery,
|
||||
}
|
||||
|
||||
// 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();
|
||||
if (battery.num_instances() >= 1) {
|
||||
Log_Write_Current_instance(battery,
|
||||
time_us,
|
||||
const uint8_t num_instances = AP::battery().num_instances();
|
||||
if (num_instances >= 1) {
|
||||
Log_Write_Current_instance(time_us,
|
||||
0,
|
||||
LOG_CURRENT_MSG,
|
||||
LOG_CURRENT_CELLS_MSG);
|
||||
}
|
||||
|
||||
if (battery.num_instances() >= 2) {
|
||||
Log_Write_Current_instance(battery,
|
||||
time_us,
|
||||
if (num_instances >= 2) {
|
||||
Log_Write_Current_instance(time_us,
|
||||
1,
|
||||
LOG_CURRENT2_MSG,
|
||||
LOG_CURRENT_CELLS2_MSG);
|
||||
|
Loading…
Reference in New Issue
Block a user