From c70c9466514661c961f29d8f4bb7ff595c4c743c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 9 Oct 2018 12:53:15 +1100 Subject: [PATCH] Copter: correct mode_zigzag compilation for ekf scalar change --- ArduCopter/mode_zigzag.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_zigzag.cpp b/ArduCopter/mode_zigzag.cpp index 783cc40c77..3570df8c22 100644 --- a/ArduCopter/mode_zigzag.cpp +++ b/ArduCopter/mode_zigzag.cpp @@ -190,7 +190,7 @@ void Copter::ModeZigZag::manual_control() motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // run loiter controller - loiter_nav->update(ekfGndSpdLimit, ekfNavVelGainScaler); + loiter_nav->update(); // call attitude controller attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);