From 8c47b0c087a87db47428910a5684d5514b5fe2c2 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 30 Jul 2012 15:43:05 -0700 Subject: [PATCH] ACM: Toy mode fix - Pitch flipped the sign on roll/Yaw coupling. --- ArduCopter/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 9c9a04d75f..52828ac3a2 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -848,7 +848,7 @@ void roll_pitch_toy() // Linear equation for Yaw:Speed to Roll // default is 1000, lower for more roll action //roll_rate = ((float)g_gps->ground_speed / 600) * (float)yaw_rate; - roll_rate = ((int32_t)g.rc_2.control_in * (yaw_rate/100)) /40; + roll_rate = -((int32_t)g.rc_2.control_in * (yaw_rate/100)) /40; //Serial.printf("roll_rate: %d\n",roll_rate); // limit roll rate to 15, 30, or 45 deg per second.