Plane: reset target altitude time on mode enter

This commit is contained in:
Nicholas Ionata 2023-08-05 10:54:35 -07:00 committed by Andrew Tridgell
parent 201e276f00
commit da30f0b418
1 changed files with 1 additions and 0 deletions

View File

@ -59,6 +59,7 @@ bool Mode::enter()
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
plane.guided_state.target_airspeed_cm = -1; // same as above, although an airspeed of -1 is rare on plane.
plane.guided_state.target_alt = -1; // same as above, although a target alt of -1 is rare on plane.
plane.guided_state.target_alt_time_ms = 0;
plane.guided_state.last_target_alt = 0;
#endif