mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: set_takeoff_expected should only get set when not flying
This commit is contained in:
parent
3a1d2f1852
commit
062a15ce11
@ -561,7 +561,7 @@ void Plane::set_servos_controlled(void)
|
||||
|
||||
// let EKF know to start GSF yaw estimator before takeoff movement starts so that yaw angle is better estimated
|
||||
const float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
||||
if (arming.is_armed()) {
|
||||
if (!is_flying() && arming.is_armed()) {
|
||||
// Check if rate of change of velocity along X axis exceeds 1-g which normally indicates a throw.
|
||||
// Tests with hand carriage of micro UAS indicates that a 1-g threshold does not false trigger prior
|
||||
// to the throw, but there is margin to increase this threshold if false triggering becomes problematic.
|
||||
|
Loading…
Reference in New Issue
Block a user