From c5916a8b4d99eabf5d72abd43f5a923b966f771d Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 7 Jun 2012 22:40:25 -0400 Subject: [PATCH] Opening up the Yaw Rate constraint for Trad Heli. --- ArduCopter/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index d3302227ef..0b210c5beb 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -255,7 +255,7 @@ get_rate_yaw(int32_t target_rate) // output control: #if FRAME_CONFIG == HELI_FRAME - int16_t yaw_limit = 2800 + abs(g.rc_4.control_in); + int16_t yaw_limit = 4500; #else int16_t yaw_limit = 1400 + abs(g.rc_4.control_in); #endif