mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
log all raw diff pres and airspeed
This commit is contained in:
parent
0fa79eab5c
commit
46a697787f
@ -1283,6 +1283,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
struct log_LAND_s log_LAND;
|
||||
struct log_RPL6_s log_RPL6;
|
||||
struct log_LOAD_s log_LOAD;
|
||||
struct log_DPRS_s log_DPRS;
|
||||
} body;
|
||||
} log_msg = {
|
||||
LOG_PACKET_HEADER_INIT(0)
|
||||
@ -1332,6 +1333,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
int land_detected_sub;
|
||||
int commander_state_sub;
|
||||
int cpuload_sub;
|
||||
int diff_pres_sub;
|
||||
} subs;
|
||||
|
||||
subs.cmd_sub = -1;
|
||||
@ -1374,6 +1376,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
subs.land_detected_sub = -1;
|
||||
subs.commander_state_sub = -1;
|
||||
subs.cpuload_sub = -1;
|
||||
subs.diff_pres_sub = -1;
|
||||
|
||||
/* add new topics HERE */
|
||||
|
||||
@ -1723,8 +1726,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
log_msg.body.log_SENS.baro_pres = 0;
|
||||
log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter;
|
||||
log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius;
|
||||
log_msg.body.log_SENS.diff_pres = 0;
|
||||
log_msg.body.log_SENS.diff_pres_filtered = 0;
|
||||
LOGBUFFER_WRITE_AND_COUNT(SENS);
|
||||
}
|
||||
}
|
||||
@ -2039,12 +2040,25 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
/* --- AIRSPEED --- */
|
||||
if (copy_if_updated(ORB_ID(airspeed), &subs.airspeed_sub, &buf.airspeed)) {
|
||||
log_msg.msg_type = LOG_AIRS_MSG;
|
||||
log_msg.body.log_AIRS.indicated_airspeed = buf.airspeed.indicated_airspeed_m_s;
|
||||
log_msg.body.log_AIRS.true_airspeed = buf.airspeed.true_airspeed_m_s;
|
||||
log_msg.body.log_AIRS.indicated_airspeed_m_s = buf.airspeed.indicated_airspeed_m_s;
|
||||
log_msg.body.log_AIRS.true_airspeed_m_s = buf.airspeed.true_airspeed_m_s;
|
||||
log_msg.body.log_AIRS.true_airspeed_unfiltered_m_s = buf.airspeed.true_airspeed_unfiltered_m_s;
|
||||
log_msg.body.log_AIRS.air_temperature_celsius = buf.airspeed.air_temperature_celsius;
|
||||
log_msg.body.log_AIRS.confidence = buf.airspeed.confidence;
|
||||
LOGBUFFER_WRITE_AND_COUNT(AIRS);
|
||||
}
|
||||
|
||||
/* --- DIFFERENTIAL PRESSURE --- */
|
||||
if (copy_if_updated(ORB_ID(differential_pressure), &subs.diff_pres_sub, &buf.diff_pres)) {
|
||||
log_msg.msg_type = LOG_DPRS_MSG;
|
||||
log_msg.body.log_DPRS.error_count = buf.diff_pres.error_count;
|
||||
log_msg.body.log_DPRS.differential_pressure_raw_pa = buf.diff_pres.differential_pressure_raw_pa;
|
||||
log_msg.body.log_DPRS.differential_pressure_filtered_pa = buf.diff_pres.differential_pressure_filtered_pa;
|
||||
log_msg.body.log_DPRS.max_differential_pressure_pa = buf.diff_pres.max_differential_pressure_pa;
|
||||
log_msg.body.log_DPRS.temperature = buf.diff_pres.temperature;
|
||||
LOGBUFFER_WRITE_AND_COUNT(DPRS);
|
||||
}
|
||||
|
||||
/* --- ESCs --- */
|
||||
if (copy_if_updated(ORB_ID(esc_status), &subs.esc_sub, &buf.esc)) {
|
||||
for (uint8_t i = 0; i < buf.esc.esc_count; i++) {
|
||||
|
||||
@ -102,8 +102,6 @@ struct log_SENS_s {
|
||||
float baro_pres;
|
||||
float baro_alt;
|
||||
float baro_temp;
|
||||
float diff_pres;
|
||||
float diff_pres_filtered;
|
||||
};
|
||||
|
||||
/* --- LPOS - LOCAL POSITION --- */
|
||||
@ -201,9 +199,11 @@ struct log_OUT_s {
|
||||
/* --- AIRS - AIRSPEED --- */
|
||||
#define LOG_AIRS_MSG 13
|
||||
struct log_AIRS_s {
|
||||
float indicated_airspeed;
|
||||
float true_airspeed;
|
||||
float indicated_airspeed_m_s;
|
||||
float true_airspeed_m_s;
|
||||
float true_airspeed_unfiltered_m_s;
|
||||
float air_temperature_celsius;
|
||||
float confidence;
|
||||
};
|
||||
|
||||
/* --- ARSP - ATTITUDE RATE SET POINT --- */
|
||||
@ -624,6 +624,16 @@ struct log_LOAD_s {
|
||||
float cpu_load;
|
||||
};
|
||||
|
||||
/* --- DPRS - DIFFERENTIAL PRESSURE --- */
|
||||
#define LOG_DPRS_MSG 62
|
||||
struct log_DPRS_s {
|
||||
uint64_t error_count;
|
||||
float differential_pressure_raw_pa;
|
||||
float differential_pressure_filtered_pa;
|
||||
float max_differential_pressure_pa;
|
||||
float temperature;
|
||||
};
|
||||
|
||||
/********** SYSTEM MESSAGES, ID > 0x80 **********/
|
||||
|
||||
/* --- TIME - TIME STAMP --- */
|
||||
@ -658,7 +668,7 @@ static const struct log_format_s log_formats[] = {
|
||||
LOG_FORMAT_S(IMU, IMU, "ffffffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,tA,tG,tM"),
|
||||
LOG_FORMAT_S(IMU1, IMU, "ffffffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,tA,tG,tM"),
|
||||
LOG_FORMAT_S(IMU2, IMU, "ffffffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,tA,tG,tM"),
|
||||
LOG_FORMAT_S(SENS, SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
|
||||
LOG_FORMAT_S(SENS, SENS, "fff", "BaroPres,BaroAlt,BaroTemp"),
|
||||
LOG_FORMAT_S(AIR1, SENS, "fffff", "BaroPa,BaroAlt,BaroTmp,DiffPres,DiffPresF"),
|
||||
LOG_FORMAT(LPOS, "ffffffffLLfBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,GFlg,EPH,EPV"),
|
||||
LOG_FORMAT(LPSP, "ffffffffff", "X,Y,Z,Yaw,VX,VY,VZ,AX,AY,AZ"),
|
||||
@ -672,7 +682,7 @@ static const struct log_format_s log_formats[] = {
|
||||
LOG_FORMAT(RC, "ffffffffffffBBBL", "C0,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,RSSI,CNT,Lost,Drop"),
|
||||
LOG_FORMAT_S(OUT0, OUT, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
|
||||
LOG_FORMAT_S(OUT1, OUT, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
|
||||
LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
|
||||
LOG_FORMAT(AIRS, "fffff", "IAS,TAS,TASraw,Temp,Confidence"),
|
||||
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
|
||||
LOG_FORMAT(FLOW, "BffffffLLHhB", "ID,RawX,RawY,RX,RY,RZ,Dist,TSpan,DtSonar,FrmCnt,GT,Qlty"),
|
||||
LOG_FORMAT(GPOS, "LLfffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV,TALT"),
|
||||
@ -713,6 +723,7 @@ static const struct log_format_s log_formats[] = {
|
||||
LOG_FORMAT(RPL6, "Qff", "Tasp,inAsp,trAsp"),
|
||||
LOG_FORMAT(LAND, "B", "Landed"),
|
||||
LOG_FORMAT(LOAD, "f", "CPU"),
|
||||
LOG_FORMAT(DPRS, "Qffff", "errors,DPRESraw,DPRES,DPRESmax,Temp"),
|
||||
/* system-level messages, ID >= 0x80 */
|
||||
/* FMT: don't write format of format message, it's useless */
|
||||
LOG_FORMAT(TIME, "Q", "StartTime"),
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user