Tracker: log the navigation alt offset

useful diagnostic, set just once
This commit is contained in:
Peter Barker 2024-01-29 14:30:55 +11:00 committed by Andrew Tridgell
parent 740ad3333a
commit 7235e6cb6a
2 changed files with 4 additions and 0 deletions

View File

@ -91,6 +91,7 @@ void Tracker::Log_Write_Vehicle_Startup_Messages()
{
logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED);
gps.Write_AP_Logger_Log_Startup_messages();
logger.Write_NamedValueFloat("NAV_ALT_OFS", nav_status.altitude_offset);
}
void Tracker::log_init(void)

View File

@ -166,6 +166,9 @@ void Tracker::tracking_update_pressure(const mavlink_scaled_pressure_t &msg)
nav_status.altitude_offset = -alt_diff;
nav_status.alt_difference_baro = 0;
nav_status.need_altitude_calibration = false;
#if HAL_LOGGING_ENABLED
logger.Write_NamedValueFloat("NAV_ALT_OFS", nav_status.altitude_offset);
#endif
}
}