mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tracker: log the navigation alt offset
useful diagnostic, set just once
This commit is contained in:
parent
740ad3333a
commit
7235e6cb6a
@ -91,6 +91,7 @@ void Tracker::Log_Write_Vehicle_Startup_Messages()
|
|||||||
{
|
{
|
||||||
logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED);
|
logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED);
|
||||||
gps.Write_AP_Logger_Log_Startup_messages();
|
gps.Write_AP_Logger_Log_Startup_messages();
|
||||||
|
logger.Write_NamedValueFloat("NAV_ALT_OFS", nav_status.altitude_offset);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Tracker::log_init(void)
|
void Tracker::log_init(void)
|
||||||
|
@ -166,6 +166,9 @@ void Tracker::tracking_update_pressure(const mavlink_scaled_pressure_t &msg)
|
|||||||
nav_status.altitude_offset = -alt_diff;
|
nav_status.altitude_offset = -alt_diff;
|
||||||
nav_status.alt_difference_baro = 0;
|
nav_status.alt_difference_baro = 0;
|
||||||
nav_status.need_altitude_calibration = false;
|
nav_status.need_altitude_calibration = false;
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
|
logger.Write_NamedValueFloat("NAV_ALT_OFS", nav_status.altitude_offset);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user