AP_Logger: move BAT & BCL logging functions to AP_BattMonitor

This commit is contained in:
Josh Henderson 2021-01-11 20:43:14 -05:00 committed by Peter Barker
parent e91953fa3b
commit 8e705a5eed
3 changed files with 3 additions and 124 deletions

View File

@ -320,7 +320,6 @@ public:
void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t esc_temp, uint16_t current_tot, int16_t motor_temp, float error_rate = 0.0f);
void Write_ServoStatus(uint64_t time_us, uint8_t id, float position, float force, float speed, uint8_t power_pct);
void Write_ESCStatus(uint64_t time_us, uint8_t id, uint32_t error_count, float voltage, float current, float temperature, int32_t rpm, uint8_t power_pct);
void Write_Current();
void Write_Compass();
void Write_Mode(uint8_t mode, const ModeReason reason);
@ -518,7 +517,6 @@ private:
void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance);
void Write_IMU_instance(uint64_t time_us, uint8_t imu_instance);
void Write_Compass_instance(uint64_t time_us, uint8_t mag_instance);
void Write_Current_instance(uint64_t time_us, uint8_t battery_instance);
void backend_starting_new_log(const AP_Logger_Backend *backend);

View File

@ -2,7 +2,6 @@
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
@ -509,70 +508,6 @@ void AP_Logger::Write_Trigger(const Location &current_loc)
Write_CameraInfo(LOG_TRIGGER_MSG, current_loc, 0);
}
void AP_Logger::Write_Current_instance(const uint64_t time_us,
const uint8_t battery_instance)
{
AP_BattMonitor &battery = AP::battery();
float temp;
bool has_temp = battery.get_temperature(temp, battery_instance);
float current, consumed_mah, consumed_wh;
if (!battery.current_amps(current, battery_instance)) {
current = quiet_nanf();
}
if (!battery.consumed_mah(consumed_mah, battery_instance)) {
consumed_mah = quiet_nanf();
}
if (!battery.consumed_wh(consumed_wh, battery_instance)) {
consumed_wh = quiet_nanf();
}
const struct log_Current pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
time_us : time_us,
instance : battery_instance,
voltage : battery.voltage(battery_instance),
voltage_resting : battery.voltage_resting_estimate(battery_instance),
current_amps : current,
current_total : consumed_mah,
consumed_wh : consumed_wh,
temperature : (int16_t)(has_temp ? (temp * 100) : 0),
resistance : battery.get_resistance(battery_instance)
};
WriteBlock(&pkt, sizeof(pkt));
// individual cell voltages
if (battery.has_cell_voltages(battery_instance)) {
const AP_BattMonitor::cells &cells = battery.get_cell_voltages(battery_instance);
struct log_Current_Cells cell_pkt{
LOG_PACKET_HEADER_INIT(LOG_CURRENT_CELLS_MSG),
time_us : time_us,
instance : battery_instance,
voltage : battery.voltage(battery_instance)
};
for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
cell_pkt.cell_voltages[i] = cells.cells[i] + 1;
}
WriteBlock(&cell_pkt, sizeof(cell_pkt));
// check battery structure can hold all cells
static_assert(ARRAY_SIZE(cells.cells) == (sizeof(cell_pkt.cell_voltages) / sizeof(cell_pkt.cell_voltages[0])),
"Battery cell number doesn't match in library and log structure");
}
}
// Write an Current data packet
void AP_Logger::Write_Current()
{
AP_BattMonitor &battery = AP::battery();
const uint64_t time_us = AP_HAL::micros64();
const uint8_t num_instances = AP::battery().num_instances();
for (uint8_t i = 0; i < num_instances; i++) {
if (battery.get_type(i) != AP_BattMonitor::Type::NONE) {
Write_Current_instance(time_us, i);
}
}
}
void AP_Logger::Write_Compass_instance(const uint64_t time_us, const uint8_t mag_instance)
{
const Compass &compass = AP::compass();

View File

@ -120,6 +120,7 @@ const struct MultiplierStructure log_Multipliers[] = {
#include <AP_DAL/LogStructure.h>
#include <AP_NavEKF2/LogStructure.h>
#include <AP_NavEKF3/LogStructure.h>
#include <AP_BattMonitor/LogStructure.h>
#include <AP_AHRS/LogStructure.h>
@ -508,19 +509,6 @@ struct PACKED log_PID {
uint8_t limit;
};
struct PACKED log_Current {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
float voltage;
float voltage_resting;
float current_amps;
float current_total;
float consumed_wh;
int16_t temperature; // degrees C * 100
float resistance;
};
struct PACKED log_WheelEncoder {
LOG_PACKET_HEADER;
uint64_t time_us;
@ -543,14 +531,6 @@ struct PACKED log_ADSB {
uint16_t squawk;
};
struct PACKED log_Current_Cells {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
float voltage;
uint16_t cell_voltages[12];
};
struct PACKED log_MAG {
LOG_PACKET_HEADER;
uint64_t time_us;
@ -1065,36 +1045,6 @@ struct PACKED log_PSC {
// @Field: GndTemp: temperature on ground, specified by parameter or measured while on ground
// @Field: Health: true if barometer is considered healthy
// @LoggerMessage: BAT
// @Description: Gathered battery data
// @Field: TimeUS: Time since system startup
// @Field: Instance: battery instance number
// @Field: Volt: measured voltage
// @Field: VoltR: estimated resting voltage
// @Field: Curr: measured current
// @Field: CurrTot: current * time
// @Field: EnrgTot: energy this battery has produced
// @Field: Temp: measured temperature
// @Field: Res: estimated battery resistance
// @LoggerMessage: BCL
// @Description: Battery cell voltage information
// @Field: TimeUS: Time since system startup
// @Field: Instance: battery instance number
// @Field: Volt: battery voltage
// @Field: V1: first cell voltage
// @Field: V2: second cell voltage
// @Field: V3: third cell voltage
// @Field: V4: fourth cell voltage
// @Field: V5: fifth cell voltage
// @Field: V6: sixth cell voltage
// @Field: V7: seventh cell voltage
// @Field: V8: eighth cell voltage
// @Field: V9: ninth cell voltage
// @Field: V10: tenth cell voltage
// @Field: V11: eleventh cell voltage
// @Field: V12: twelfth cell voltage
// @LoggerMessage: BCN
// @Description: Beacon informtaion
// @Field: TimeUS: Time since system startup
@ -1803,10 +1753,7 @@ struct PACKED log_PSC {
{ LOG_TRIGGER_MSG, sizeof(log_Camera), \
"TRIG", "QIHLLeeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,Roll,Pitch,Yaw", "s--DUmmmddd", "F--GGBBBBBB" }, \
{ LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBfB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hfp,Pri", "s#nPOPP----", "F-00B00----" }, \
{ LOG_CURRENT_MSG, sizeof(log_Current), \
"BAT", "QBfffffcf", "TimeUS,Instance,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res", "s#vvAiJOw", "F-000!/?0" }, \
{ LOG_CURRENT_CELLS_MSG, sizeof(log_Current_Cells), \
"BCL", "QBfHHHHHHHHHHHH", "TimeUS,Instance,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10,V11,V12", "s#vvvvvvvvvvvvv", "F-0CCCCCCCCCCCC" }, \
LOG_STRUCTURE_FROM_BATTMONITOR \
{ LOG_MAG_MSG, sizeof(log_MAG), \
"MAG", "QBhhhhhhhhhBI", "TimeUS,I,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOX,MOY,MOZ,Health,S", "s#GGGGGGGGG-s", "F-CCCCCCCCC-F" }, \
{ LOG_MODE_MSG, sizeof(log_Mode), \
@ -1966,8 +1913,7 @@ enum LogMessages : uint8_t {
LOG_CSRV_MSG,
LOG_CESC_MSG,
LOG_ARSP_MSG,
LOG_CURRENT_MSG,
LOG_CURRENT_CELLS_MSG,
LOG_IDS_FROM_BATTMONITOR,
LOG_MAG_MSG,
LOG_MODE_MSG,
LOG_GPS_RAW_MSG,