Skip to content

Commit 7aae436

Browse files
committed
Plane: fixed clear of inverted flight for tailsitters
1 parent 416d672 commit 7aae436

File tree

1 file changed

+4
-3
lines changed

1 file changed

+4
-3
lines changed

ArduPlane/tailsitter.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -562,9 +562,6 @@ bool Tailsitter::transition_vtol_complete(void) const
562562
const float trans_angle = get_transition_angle_vtol();
563563
if (labs(plane.ahrs.pitch_sensor) > trans_angle*100) {
564564
gcs().send_text(MAV_SEVERITY_INFO, "Transition VTOL done");
565-
// clear inverted flight flag to make behaviour consistent
566-
// with other quadplane types
567-
plane.inverted_flight = false;
568565
return true;
569566
}
570567
int32_t roll_cd = labs(plane.ahrs.roll_sensor);
@@ -905,6 +902,10 @@ void Tailsitter_Transition::VTOL_update()
905902
vtol_limit_start_ms = now;
906903
vtol_limit_initial_pitch = quadplane.ahrs_view->pitch_sensor;
907904
}
905+
906+
// clear inverted flight flag to make behaviour consistent
907+
// with other quadplane types
908+
plane.inverted_flight = false;
908909
} else {
909910
// Keep assistance reset while not checking
910911
quadplane.assist.reset();

0 commit comments

Comments
 (0)