mirror of https://github.com/ArduPilot/ardupilot
Plane: make detection of impending takeoff more likely
This commit is contained in:
parent
a1bde16abd
commit
39e1eb238d
|
@ -556,8 +556,8 @@ 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 (!is_flying() && arming.is_armed()) {
|
||||
bool throw_detected = sq(ahrs.get_accel_ef().x) + sq(ahrs.get_accel_ef().y) > sq(g.takeoff_throttle_min_accel);
|
||||
if (arming.is_armed()) {
|
||||
bool throw_detected = ahrs.get_accel().x - GRAVITY_MSS * ahrs.sin_pitch() > GRAVITY_MSS;
|
||||
bool throttle_up_detected = throttle > aparm.throttle_cruise;
|
||||
if (throw_detected || throttle_up_detected) {
|
||||
plane.ahrs.setTakeoffExpected(true);
|
||||
|
|
Loading…
Reference in New Issue