mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Plane: Don't set takeoff expected until vehicle is armed.
This commit is contained in:
parent
295c1e1308
commit
ad582a90dd
@ -61,7 +61,7 @@ bool Plane::auto_takeoff_check(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// let EKF know to start GSF yaw estimator before takeoff movement starts so that yaw angle is better estimated
|
// let EKF know to start GSF yaw estimator before takeoff movement starts so that yaw angle is better estimated
|
||||||
plane.ahrs.setTakeoffExpected(true);
|
plane.ahrs.setTakeoffExpected(arming.is_armed());
|
||||||
|
|
||||||
// we've reached the acceleration threshold, so start the timer
|
// we've reached the acceleration threshold, so start the timer
|
||||||
if (!takeoff_state.launchTimerStarted) {
|
if (!takeoff_state.launchTimerStarted) {
|
||||||
|
Loading…
Reference in New Issue
Block a user