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 Randy Mackay
parent d48b95c4a7
commit 3a7c0a6e7e

View File

@ -56,6 +56,7 @@ bool Mode::enter()
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE; 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_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 = -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; plane.guided_state.last_target_alt = 0;
#endif #endif