Rover: use ahrs singleton to log ATT, POS and AHRS2

This commit is contained in:
Peter Barker 2019-10-24 11:32:42 +11:00 committed by Peter Barker
parent c30873097a
commit 3fff2eaf6d
1 changed files with 3 additions and 3 deletions

View File

@ -10,13 +10,13 @@ void Rover::Log_Write_Attitude()
float desired_pitch_cd = degrees(g2.attitude_control.get_desired_pitch()) * 100.0f;
const Vector3f targets(0.0f, desired_pitch_cd, 0.0f);
logger.Write_Attitude(ahrs, targets);
logger.Write_Attitude(targets);
#if AP_AHRS_NAVEKF_AVAILABLE
AP::ahrs_navekf().Log_Write();
logger.Write_AHRS2(ahrs);
logger.Write_AHRS2();
#endif
logger.Write_POS(ahrs);
logger.Write_POS();
// log steering rate controller
logger.Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info());