From b4be1b866a64a4807b3a9fb1ce4fd375e257609d Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 15 May 2015 08:54:46 -0700 Subject: [PATCH] Copter: compiler warning stuff float to double promotion via cos instead of cosf --- ArduPlane/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 8d44203c18..63a209590e 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -1026,7 +1026,7 @@ static void update_load_factor(void) // limit to 85 degrees to prevent numerical errors demanded_roll = 85; } - aerodynamic_load_factor = 1.0f / safe_sqrt(cos(radians(demanded_roll))); + aerodynamic_load_factor = 1.0f / safe_sqrt(cosf(radians(demanded_roll))); if (!aparm.stall_prevention) { // stall prevention is disabled