AP_Logger: use instance number for Baro logging
This commit is contained in:
parent
2437cf8a24
commit
12f0e9dd43
@ -458,7 +458,7 @@ private:
|
||||
// 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, enum LogMessages type);
|
||||
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,
|
||||
|
@ -265,15 +265,16 @@ void AP_Logger::Write_RSSI()
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
|
||||
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(type),
|
||||
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),
|
||||
@ -293,12 +294,8 @@ void AP_Logger::Write_Baro(uint64_t time_us)
|
||||
time_us = AP_HAL::micros64();
|
||||
}
|
||||
const AP_Baro &baro = AP::baro();
|
||||
Write_Baro_instance(time_us, 0, LOG_BARO_MSG);
|
||||
if (baro.num_instances() > 1) {
|
||||
Write_Baro_instance(time_us, 1, LOG_BAR2_MSG);
|
||||
}
|
||||
if (baro.num_instances() > 2) {
|
||||
Write_Baro_instance(time_us, 2, LOG_BAR3_MSG);
|
||||
for (uint8_t i=0; i< baro.num_instances(); i++) {
|
||||
Write_Baro_instance(time_us, i);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -359,6 +359,7 @@ struct PACKED log_RSSI {
|
||||
struct PACKED log_BARO {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint8_t instance;
|
||||
float altitude;
|
||||
float pressure;
|
||||
int16_t temperature;
|
||||
@ -1310,12 +1311,6 @@ struct PACKED log_PSC {
|
||||
// UNIT messages define units which can be referenced by FMTU messages
|
||||
// FMTU messages associate types (e.g. centimeters/second/second) to FMT message fields
|
||||
|
||||
// see "struct sensor" in AP_Baro.h and "Write_Baro":
|
||||
#define BARO_LABELS "TimeUS,Alt,Press,Temp,CRt,SMS,Offset,GndTemp,Health"
|
||||
#define BARO_FMT "QffcfIffB"
|
||||
#define BARO_UNITS "smPOnsmO-"
|
||||
#define BARO_MULTS "F00B0C?0-"
|
||||
|
||||
#define GPA_LABELS "TimeUS,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta"
|
||||
#define GPA_FMT "QCCCCfBIH"
|
||||
#define GPA_UNITS "smmmnd-ss"
|
||||
@ -1430,9 +1425,10 @@ struct PACKED log_PSC {
|
||||
// @Field: ErrRP: lowest estimated gyro drift error
|
||||
// @Field: ErrYaw: difference between measured yaw and DCM yaw estimate
|
||||
|
||||
// @LoggerMessage: BARO,BAR2,BAR3
|
||||
// @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
|
||||
@ -2536,7 +2532,7 @@ struct PACKED log_PSC {
|
||||
{ LOG_RSSI_MSG, sizeof(log_RSSI), \
|
||||
"RSSI", "Qf", "TimeUS,RXRSSI", "s-", "F-" }, \
|
||||
{ LOG_BARO_MSG, sizeof(log_BARO), \
|
||||
"BARO", BARO_FMT, BARO_LABELS, BARO_UNITS, BARO_MULTS }, \
|
||||
"BARO", "QBffcfIffB", "TimeUS,I,Alt,Press,Temp,CRt,SMS,Offset,GndTemp,Health", "s#mPOnsmO-", "F-00B0C?0-" }, \
|
||||
{ LOG_POWR_MSG, sizeof(log_POWR), \
|
||||
"POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---" }, \
|
||||
{ LOG_CMD_MSG, sizeof(log_Cmd), \
|
||||
@ -2657,10 +2653,6 @@ struct PACKED log_PSC {
|
||||
"PIDS", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
||||
{ LOG_DSTL_MSG, sizeof(log_DSTL), \
|
||||
"DSTL", "QBfLLeccfeffff", "TimeUS,Stg,THdg,Lat,Lng,Alt,XT,Travel,L1I,Loiter,Des,P,I,D", "s??DUm--------", "F??000--------" }, \
|
||||
{ LOG_BAR2_MSG, sizeof(log_BARO), \
|
||||
"BAR2", BARO_FMT, BARO_LABELS, BARO_UNITS, BARO_MULTS }, \
|
||||
{ LOG_BAR3_MSG, sizeof(log_BARO), \
|
||||
"BAR3", BARO_FMT, BARO_LABELS, BARO_UNITS, BARO_MULTS }, \
|
||||
{ LOG_VIBE_MSG, sizeof(log_Vibe), \
|
||||
"VIBE", "QBfffI", "TimeUS,IMU,VibeX,VibeY,VibeZ,Clip", "s#----", "F-----" }, \
|
||||
{ LOG_IMUDT_MSG, sizeof(log_IMUDT), \
|
||||
@ -2788,7 +2780,6 @@ enum LogMessages : uint8_t {
|
||||
LOG_ESC_MSG,
|
||||
LOG_CSRV_MSG,
|
||||
LOG_CESC_MSG,
|
||||
LOG_BAR2_MSG,
|
||||
LOG_ARSP_MSG,
|
||||
LOG_ATTITUDE_MSG,
|
||||
LOG_CURRENT_MSG,
|
||||
@ -2828,7 +2819,6 @@ enum LogMessages : uint8_t {
|
||||
LOG_GPA2_MSG,
|
||||
LOG_GPAB_MSG,
|
||||
LOG_RFND_MSG,
|
||||
LOG_BAR3_MSG,
|
||||
LOG_MAV_STATS,
|
||||
LOG_FORMAT_UNITS_MSG,
|
||||
LOG_UNIT_MSG,
|
||||
|
Loading…
Reference in New Issue
Block a user