From ab603c7fcf214023133b966345ad3407653bb7ce Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 9 Jul 2012 13:12:14 -0700 Subject: [PATCH] Toy Mode Yaw Rate fix --- ArduCopter/Attitude.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 786b92232f..c299143d8c 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -713,11 +713,11 @@ void roll_pitch_toy() //g.rc_4.servo_out = get_stabilize_yaw(nav_yaw); if(g.rc_1.control_in != 0){ - g.rc_4.servo_out = get_acro_yaw(yaw_rate); + g.rc_4.servo_out = get_rate_yaw(yaw_rate); yaw_stopped = false; yaw_timer = 150; }else if (!yaw_stopped){ - g.rc_4.servo_out = get_acro_yaw(0); + g.rc_4.servo_out = get_rate_yaw(0); yaw_timer--; if(yaw_timer == 0){ yaw_stopped = true;