From 7b1157e2d89ea3fe52ec07dd1eb4ba5cdaf09ae3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 22 Jan 2018 12:34:38 +0900 Subject: [PATCH] Plane: remove setting accel_z PID controller's dt This is handled within pos-controller's set_dt function --- ArduPlane/quadplane.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index c80d95a92a..d6b7748203 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -534,7 +534,6 @@ bool QuadPlane::setup(void) motors->set_throttle_range(thr_min_pwm, thr_max_pwm); motors->set_update_rate(rc_speed); motors->set_interlock(true); - pos_control->get_accel_z_pid().set_dt(loop_delta_t); pos_control->set_dt(loop_delta_t); attitude_control->parameter_sanity_check();