Plane: use ahrs singleton to log ATT, POS and AHRS2
This commit is contained in:
parent
9c57862ec6
commit
1d99fbebc9
@ -27,7 +27,7 @@ void Plane::Log_Write_Attitude(void)
|
|||||||
targets *= degrees(100.0f);
|
targets *= degrees(100.0f);
|
||||||
logger.Write_AttitudeView(*quadplane.ahrs_view, targets);
|
logger.Write_AttitudeView(*quadplane.ahrs_view, targets);
|
||||||
} else {
|
} else {
|
||||||
logger.Write_Attitude(ahrs, targets);
|
logger.Write_Attitude(targets);
|
||||||
}
|
}
|
||||||
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
|
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
|
||||||
// log quadplane PIDs separately from fixed wing PIDs
|
// log quadplane PIDs separately from fixed wing PIDs
|
||||||
@ -44,12 +44,12 @@ void Plane::Log_Write_Attitude(void)
|
|||||||
|
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
AP::ahrs_navekf().Log_Write();
|
AP::ahrs_navekf().Log_Write();
|
||||||
logger.Write_AHRS2(ahrs);
|
logger.Write_AHRS2();
|
||||||
#endif
|
#endif
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
sitl.Log_Write_SIMSTATE();
|
sitl.Log_Write_SIMSTATE();
|
||||||
#endif
|
#endif
|
||||||
logger.Write_POS(ahrs);
|
logger.Write_POS();
|
||||||
}
|
}
|
||||||
|
|
||||||
// do logging at loop rate
|
// do logging at loop rate
|
||||||
|
Loading…
Reference in New Issue
Block a user