diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index bce1e5a766..f8f2cd1cbd 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -1223,13 +1223,12 @@ private: EKF_obs_buffer_t storedWheelOdm; // body velocity data buffer wheel_odm_elements wheelOdmDataDelayed; // Body frame odometry data at the fusion time horizon - // yaw sensor fusion - uint32_t yawMeasTime_ms; - EKF_obs_buffer_t storedYawAng; - yaw_elements yawAngDataNew; - yaw_elements yawAngDataDelayed; - yaw_elements yawAngDataStatic; - + // GPS yaw sensor fusion + uint32_t yawMeasTime_ms; // system time GPS yaw angle was last input to the data buffer + EKF_obs_buffer_t storedYawAng; // GPS yaw angle buffer + yaw_elements yawAngDataNew; // GPS yaw angle at the current time horizon + yaw_elements yawAngDataDelayed; // GPS yaw angle at the fusion time horizon + yaw_elements yawAngDataStatic; // yaw angle (regardless of yaw source) when the vehicle was last on ground and not moving // Range Beacon Sensor Fusion EKF_obs_buffer_t storedRangeBeacon; // Beacon range buffer