Plane: set nav_controller stale on mode change

This commit is contained in:
Tom Pittenger 2023-11-21 11:52:03 -08:00 committed by Andrew Tridgell
parent 0e9f9920bc
commit d1b2c6e564
1 changed files with 3 additions and 0 deletions

View File

@ -113,6 +113,9 @@ bool Mode::enter()
plane.adsb.set_is_auto_mode(does_auto_navigation());
#endif
// set the nav controller stale AFTER _enter() so that we can check if we're currently in a loiter during the mode change
plane.nav_controller->set_data_is_stale();
// reset steering integrator on mode change
plane.steerController.reset_I();