Plane: fixed jump in qhover on takeoff

Z controller PID is from -1 to 1

thanks to Leonard for spotting this
This commit is contained in:
Andrew Tridgell 2017-04-24 12:05:24 +10:00
parent b9debba509
commit 06b0742481

View File

@ -752,7 +752,7 @@ void QuadPlane::run_z_controller(void)
// controller. We need to assume the integrator may be way off
// the base throttle we start at is the current throttle we are using
float base_throttle = constrain_float(motors->get_throttle() - motors->get_throttle_hover(), 0, 1) * 1000;
float base_throttle = constrain_float(motors->get_throttle() - motors->get_throttle_hover(), -1, 1) * 1000;
pid_accel_z.set_integrator(base_throttle);
last_pidz_init_ms = now;