Copter: correct mode_zigzag compilation for ekf scalar change

This commit is contained in:
Peter Barker 2018-10-09 12:53:15 +11:00 committed by WickedShell
parent 14d2012f54
commit c70c946651
1 changed files with 1 additions and 1 deletions

View File

@ -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);