mirror of https://github.com/ArduPilot/ardupilot
Copter: use ahrs singleton to log ATT, POS and AHRS2
This commit is contained in:
parent
52ec1dba5e
commit
9c57862ec6
|
@ -72,7 +72,7 @@ void Copter::Log_Write_Attitude()
|
|||
{
|
||||
Vector3f targets = attitude_control->get_att_target_euler_cd();
|
||||
targets.z = wrap_360_cd(targets.z);
|
||||
logger.Write_Attitude(ahrs, targets);
|
||||
logger.Write_Attitude(targets);
|
||||
logger.Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
|
||||
if (should_log(MASK_LOG_PID)) {
|
||||
logger.Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
|
||||
|
@ -86,11 +86,11 @@ void Copter::Log_Write_Attitude()
|
|||
void Copter::Log_Write_EKF_POS()
|
||||
{
|
||||
AP::ahrs_navekf().Log_Write();
|
||||
logger.Write_AHRS2(ahrs);
|
||||
logger.Write_AHRS2();
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
sitl.Log_Write_SIMSTATE();
|
||||
#endif
|
||||
logger.Write_POS(ahrs);
|
||||
logger.Write_POS();
|
||||
}
|
||||
|
||||
struct PACKED log_MotBatt {
|
||||
|
|
Loading…
Reference in New Issue