From 5136b90d27357e54a0f0b107253f3a4fe5a311ab Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 15 Sep 2018 10:03:05 +1000 Subject: [PATCH] Plane: do attitude relax after 100ms --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 801e949856..1e0be8ef22 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -780,7 +780,7 @@ void QuadPlane::run_z_controller(void) void QuadPlane::check_attitude_relax(void) { uint32_t now = AP_HAL::millis(); - if (now - last_att_control_ms > 500) { + if (now - last_att_control_ms > 100) { attitude_control->relax_attitude_controllers(); } last_att_control_ms = now;