Skip to content

Commit

Permalink
Plane: Allow wind relative dead reckoning when lift motors are assisting
Browse files Browse the repository at this point in the history
When lift motors are assisting the wing during forward flight, the airspeed
and zero sideslip assumption are still sufficiently valid to keep navigating.
Without this patch a VTOL operating in FW mode without GPS and reliant on
air data for dead reckoning will stop navigating and lose its position estimate
if the lift motors start assisting.
  • Loading branch information
priseborough authored and peterbarker committed Dec 26, 2024
1 parent 42f1aea commit 954ffc2
Showing 1 changed file with 0 additions and 5 deletions.
5 changes: 0 additions & 5 deletions ArduPlane/Plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -533,11 +533,6 @@ void Plane::update_fly_forward(void)
ahrs.set_fly_forward(false);
return;
}

if (quadplane.in_assisted_flight()) {
ahrs.set_fly_forward(false);
return;
}
}
#endif

Expand Down

0 comments on commit 954ffc2

Please sign in to comment.