AP_Baro: Privatize Logging

This commit is contained in:
Josh Henderson 2021-01-22 23:26:33 -05:00 committed by Peter Barker
parent c32dd4bb5d
commit 275c2849cf
4 changed files with 71 additions and 1 deletions

View File

@ -895,7 +895,7 @@ void AP_Baro::update(void)
// logging
#ifndef HAL_NO_LOGGING
if (should_log()) {
AP::logger().Write_Baro();
Write_Baro();
}
#endif
}

View File

@ -311,6 +311,10 @@ private:
*/
float wind_pressure_correction(uint8_t instance);
#endif
// Logging function
void Write_Baro(void);
void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance);
};

View File

@ -0,0 +1,30 @@
#include "AP_Baro.h"
#include <AP_Logger/AP_Logger.h>
void AP_Baro::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance)
{
const struct log_BARO pkt{
LOG_PACKET_HEADER_INIT(LOG_BARO_MSG),
time_us : time_us,
instance : baro_instance,
altitude : get_altitude(baro_instance),
pressure : get_pressure(baro_instance),
temperature : (int16_t)(get_temperature(baro_instance) * 100 + 0.5f),
climbrate : get_climb_rate(),
sample_time_ms: get_last_update(baro_instance),
drift_offset : get_baro_drift_offset(),
ground_temp : get_ground_temperature(),
healthy : (uint8_t)healthy(baro_instance)
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
// Write a BARO packet
void AP_Baro::Write_Baro(void)
{
const uint64_t time_us = AP_HAL::micros64();
for (uint8_t i=0; i< _num_sensors; i++) {
Write_Baro_instance(time_us, i);
}
}

View File

@ -0,0 +1,36 @@
#pragma once
#include <AP_Logger/LogStructure.h>
#define LOG_IDS_FROM_BARO \
LOG_BARO_MSG
// @LoggerMessage: BARO
// @Description: Gathered Barometer data
// @Field: TimeUS: Time since system startup
// @Field: I: barometer sensor instance number
// @Field: Alt: calculated altitude
// @Field: Press: measured atmospheric pressure
// @Field: Temp: measured atmospheric temperature
// @Field: CRt: derived climb rate from primary barometer
// @Field: SMS: time last sample was taken
// @Field: Offset: raw adjustment of barometer altitude, zeroed on calibration, possibly set by GCS
// @Field: GndTemp: temperature on ground, specified by parameter or measured while on ground
// @Field: Health: true if barometer is considered healthy
struct PACKED log_BARO {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
float altitude;
float pressure;
int16_t temperature;
float climbrate;
uint32_t sample_time_ms;
float drift_offset;
float ground_temp;
uint8_t healthy;
};
#define LOG_STRUCTURE_FROM_BARO \
{ LOG_BARO_MSG, sizeof(log_BARO), \
"BARO", "QBffcfIffB", "TimeUS,I,Alt,Press,Temp,CRt,SMS,Offset,GndTemp,Health", "s#mPOnsmO-", "F-00B0C?0-" },