From 36cc8329314a430811c1907e6b4f1555b71e4acd Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 22 Apr 2015 12:04:27 -0700 Subject: [PATCH] Copter: guided_posvel run update_z_controller at 400hz --- ArduCopter/control_guided.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/control_guided.pde b/ArduCopter/control_guided.pde index 7fccbc2fb2..0804542b85 100644 --- a/ArduCopter/control_guided.pde +++ b/ArduCopter/control_guided.pde @@ -331,9 +331,10 @@ static void guided_posvel_control_run() // run position controller pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler); - pos_control.update_z_controller(); } + pos_control.update_z_controller(); + // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { // roll & pitch from waypoint controller, yaw rate from pilot