Plane: mode enter init auto state vtol mode to is_vtol_mode

This commit is contained in:
Iampete1 2021-09-04 20:22:35 +01:00 committed by Andrew Tridgell
parent 2582159d1a
commit e4feea9457
1 changed files with 2 additions and 2 deletions

View File

@ -65,8 +65,8 @@ bool Mode::enter()
// record time of mode change
plane.last_mode_change_ms = AP_HAL::millis();
// assume non-VTOL mode
plane.auto_state.vtol_mode = false;
// set VTOL auto state
plane.auto_state.vtol_mode = is_vtol_mode();
plane.auto_state.vtol_loiter = false;
// initialize speed variable used in AUTO and GUIDED for DO_CHANGE_SPEED commands