mirror of https://github.com/ArduPilot/ardupilot
Plane: suppress spurious EKF yaw reset message
this makes plane match copter, emitting a yaw reset event, but not worrying user. This message came out on each boot when EKF3 first became active
This commit is contained in:
parent
28e5f255b7
commit
0168b23db1
|
@ -1160,7 +1160,7 @@ void QuadPlane::check_yaw_reset(void)
|
|||
if (new_ekfYawReset_ms != ekfYawReset_ms) {
|
||||
attitude_control->inertial_frame_reset();
|
||||
ekfYawReset_ms = new_ekfYawReset_ms;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EKF yaw reset %.2f", (double)degrees(yaw_angle_change_rad));
|
||||
AP::logger().Write_Event(LogEvent::EKF_YAW_RESET);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue