Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Privatize AP_Baro logging #16457

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/AP_Baro/AP_Baro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -895,7 +895,7 @@ void AP_Baro::update(void)
// logging
#ifndef HAL_NO_LOGGING
if (should_log()) {
AP::logger().Write_Baro();
Write_Baro();
}
#endif
}
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Baro/AP_Baro.h
Original file line number Diff line number Diff line change
Expand Up @@ -311,6 +311,10 @@ class AP_Baro
*/
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);

};

Expand Down
30 changes: 30 additions & 0 deletions libraries/AP_Baro/AP_Baro_Logging.cpp
Original file line number Diff line number Diff line change
@@ -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);
}
}
36 changes: 36 additions & 0 deletions libraries/AP_Baro/LogStructure.h
Original file line number Diff line number Diff line change
@@ -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-" },
2 changes: 0 additions & 2 deletions libraries/AP_Logger/AP_Logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,6 @@ class AP_Logger
void Write_RCOUT(void);
void Write_RSSI();
void Write_Rally();
void Write_Baro();
void Write_Power(void);
void Write_Radio(const mavlink_radio_t &packet);
void Write_Message(const char *message);
Expand Down Expand Up @@ -511,7 +510,6 @@ class AP_Logger
// state to help us not log unneccesary RCIN values:
bool seen_nonzero_rcin15_or_rcin16;

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);

Expand Down
33 changes: 0 additions & 33 deletions libraries/AP_Logger/LogFile.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include <stdlib.h>

#include <AP_AHRS/AP_AHRS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
Expand Down Expand Up @@ -261,38 +260,6 @@ void AP_Logger::Write_RSSI()
WriteBlock(&pkt, sizeof(pkt));
}

void AP_Logger::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance)
{
AP_Baro &baro = AP::baro();
float climbrate = baro.get_climb_rate();
float drift_offset = baro.get_baro_drift_offset();
float ground_temp = baro.get_ground_temperature();
const struct log_BARO pkt{
LOG_PACKET_HEADER_INIT(LOG_BARO_MSG),
time_us : time_us,
instance : baro_instance,
altitude : baro.get_altitude(baro_instance),
pressure : baro.get_pressure(baro_instance),
temperature : (int16_t)(baro.get_temperature(baro_instance) * 100 + 0.5f),
climbrate : climbrate,
sample_time_ms: baro.get_last_update(baro_instance),
drift_offset : drift_offset,
ground_temp : ground_temp,
healthy : (uint8_t)baro.healthy(baro_instance)
};
WriteBlock(&pkt, sizeof(pkt));
}

// Write a BARO packet
void AP_Logger::Write_Baro()
{
const uint64_t time_us = AP_HAL::micros64();
const AP_Baro &baro = AP::baro();
for (uint8_t i=0; i< baro.num_instances(); i++) {
Write_Baro_instance(time_us, i);
}
}

void AP_Logger::Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance)
{
const AP_InertialSensor &ins = AP::ins();
Expand Down
34 changes: 3 additions & 31 deletions libraries/AP_Logger/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,9 +121,9 @@ const struct MultiplierStructure log_Multipliers[] = {
#include <AP_NavEKF2/LogStructure.h>
#include <AP_NavEKF3/LogStructure.h>
#include <AP_BattMonitor/LogStructure.h>

#include <AP_AHRS/LogStructure.h>
#include <AP_Camera/LogStructure.h>
#include <AP_Baro/LogStructure.h>

// structure used to define logging format
struct LogStructure {
Expand Down Expand Up @@ -354,20 +354,6 @@ struct PACKED log_RSSI {
float RXRSSI;
};

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;
};

struct PACKED log_Optflow {
LOG_PACKET_HEADER;
uint64_t time_us;
Expand Down Expand Up @@ -1018,19 +1004,6 @@ struct PACKED log_PSC {
// @Field: Hfp: Probability sensor has failed
// @Field: Pri: True if sensor is the primary sensor

// @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

// @LoggerMessage: BCN
// @Description: Beacon informtaion
// @Field: TimeUS: Time since system startup
Expand Down Expand Up @@ -1710,8 +1683,7 @@ struct PACKED log_PSC {
"RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------" }, \
{ LOG_RSSI_MSG, sizeof(log_RSSI), \
"RSSI", "Qf", "TimeUS,RXRSSI", "s-", "F-" }, \
{ LOG_BARO_MSG, sizeof(log_BARO), \
"BARO", "QBffcfIffB", "TimeUS,I,Alt,Press,Temp,CRt,SMS,Offset,GndTemp,Health", "s#mPOnsmO-", "F-00B0C?0-" }, \
LOG_STRUCTURE_FROM_BARO \
{ LOG_POWR_MSG, sizeof(log_POWR), \
"POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---" }, \
{ LOG_CMD_MSG, sizeof(log_Cmd), \
Expand Down Expand Up @@ -1866,7 +1838,7 @@ enum LogMessages : uint8_t {
LOG_RCIN2_MSG,
LOG_RCOUT_MSG,
LOG_RSSI_MSG,
LOG_BARO_MSG,
LOG_IDS_FROM_BARO,
LOG_POWR_MSG,
LOG_IDS_FROM_AHRS,
LOG_SIMSTATE_MSG,
Expand Down