ArduPlane: Poll AP_Landing for fly forward information
This commit is contained in:
parent
64fb09fb38
commit
92d505598b
@ -601,6 +601,8 @@ void Plane::update_flight_mode(void)
|
||||
if (quadplane.in_vtol_mode() ||
|
||||
quadplane.in_assisted_flight()) {
|
||||
ahrs.set_fly_forward(false);
|
||||
} else if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
ahrs.set_fly_forward(landing.is_flying_forward());
|
||||
} else {
|
||||
ahrs.set_fly_forward(true);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user