Plane: added baro and airspeed logging
including raw temperature and pressure values
This commit is contained in:
parent
cf1f05a198
commit
906fc17905
@ -519,6 +519,36 @@ static void Log_Write_RC(void)
|
|||||||
DataFlash.Log_Write_RCOUT();
|
DataFlash.Log_Write_RCOUT();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void Log_Write_Baro(void)
|
||||||
|
{
|
||||||
|
DataFlash.Log_Write_Baro(barometer);
|
||||||
|
}
|
||||||
|
|
||||||
|
struct PACKED log_AIRSPEED {
|
||||||
|
LOG_PACKET_HEADER;
|
||||||
|
uint32_t timestamp;
|
||||||
|
float airspeed;
|
||||||
|
float diffpressure;
|
||||||
|
int16_t temperature;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Write a AIRSPEED packet
|
||||||
|
static void Log_Write_Airspeed(void)
|
||||||
|
{
|
||||||
|
float temperature;
|
||||||
|
if (!airspeed.get_temperature(temperature)) {
|
||||||
|
temperature = 0;
|
||||||
|
}
|
||||||
|
struct log_AIRSPEED pkt = {
|
||||||
|
LOG_PACKET_HEADER_INIT(LOG_AIRSPEED_MSG),
|
||||||
|
timestamp : hal.scheduler->millis(),
|
||||||
|
airspeed : airspeed.get_raw_airspeed(),
|
||||||
|
diffpressure : airspeed.get_differential_pressure(),
|
||||||
|
temperature : (int16_t)(temperature * 100.0f)
|
||||||
|
};
|
||||||
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
|
}
|
||||||
|
|
||||||
static const struct LogStructure log_structure[] PROGMEM = {
|
static const struct LogStructure log_structure[] PROGMEM = {
|
||||||
LOG_COMMON_STRUCTURES,
|
LOG_COMMON_STRUCTURES,
|
||||||
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
||||||
@ -547,6 +577,8 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
|||||||
"MAG2", "Ihhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ" },
|
"MAG2", "Ihhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ" },
|
||||||
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
|
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
|
||||||
"ARM", "IHB", "TimeMS,ArmState,ArmChecks" },
|
"ARM", "IHB", "TimeMS,ArmState,ArmChecks" },
|
||||||
|
{ LOG_AIRSPEED_MSG, sizeof(log_AIRSPEED),
|
||||||
|
"ARSP", "Iffc", "TimeMS,Airspeed,DiffPress,Temp" },
|
||||||
TECS_LOG_FORMAT(LOG_TECS_MSG),
|
TECS_LOG_FORMAT(LOG_TECS_MSG),
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -597,6 +629,8 @@ static void Log_Write_Compass() {}
|
|||||||
static void Log_Write_GPS() {}
|
static void Log_Write_GPS() {}
|
||||||
static void Log_Write_IMU() {}
|
static void Log_Write_IMU() {}
|
||||||
static void Log_Write_RC() {}
|
static void Log_Write_RC() {}
|
||||||
|
static void Log_Write_Airspeed(void) {}
|
||||||
|
static void Log_Write_Baro(void) {}
|
||||||
|
|
||||||
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
|
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -143,6 +143,7 @@ enum log_messages {
|
|||||||
LOG_SONAR_MSG,
|
LOG_SONAR_MSG,
|
||||||
LOG_COMPASS2_MSG,
|
LOG_COMPASS2_MSG,
|
||||||
LOG_ARM_DISARM_MSG,
|
LOG_ARM_DISARM_MSG,
|
||||||
|
LOG_AIRSPEED_MSG,
|
||||||
MAX_NUM_LOGS // always at the end
|
MAX_NUM_LOGS // always at the end
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -20,6 +20,9 @@ static void init_barometer(void)
|
|||||||
static int32_t read_barometer(void)
|
static int32_t read_barometer(void)
|
||||||
{
|
{
|
||||||
barometer.read();
|
barometer.read();
|
||||||
|
if (should_log(MASK_LOG_IMU)) {
|
||||||
|
Log_Write_Baro();
|
||||||
|
}
|
||||||
return altitude_filter.apply(barometer.get_altitude() * 100.0);
|
return altitude_filter.apply(barometer.get_altitude() * 100.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -51,6 +54,9 @@ static void read_airspeed(void)
|
|||||||
{
|
{
|
||||||
if (airspeed.enabled()) {
|
if (airspeed.enabled()) {
|
||||||
airspeed.read();
|
airspeed.read();
|
||||||
|
if (should_log(MASK_LOG_IMU)) {
|
||||||
|
Log_Write_Airspeed();
|
||||||
|
}
|
||||||
calc_airspeed_errors();
|
calc_airspeed_errors();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user