diff --git a/ArduCopter/control_guided.cpp b/ArduCopter/control_guided.cpp index ef519e1bec..759aa88ee5 100644 --- a/ArduCopter/control_guided.cpp +++ b/ArduCopter/control_guided.cpp @@ -305,19 +305,8 @@ void Copter::guided_vel_control_run() pos_control.set_desired_velocity(Vector3f(0,0,0)); } - // calculate dt - float dt = pos_control.time_since_last_xy_update(); - - // update at poscontrol update rate - if (dt >= pos_control.get_dt_xy()) { - // sanity check dt - if (dt >= 0.2f) { - dt = 0.0f; - } - - // call velocity controller which includes z axis controller - pos_control.update_vel_controller_xyz(ekfNavVelGainScaler); - } + // call velocity controller which includes z axis controller + pos_control.update_vel_controller_xyz(ekfNavVelGainScaler); // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) {