From f87ab2106307902fb2509ffa8a376e1607f640e8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 16 Apr 2014 21:03:29 +0900 Subject: [PATCH] Copter: Hybrid estimates wind when speed under 10cm/s --- ArduCopter/control_hybrid.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_hybrid.pde b/ArduCopter/control_hybrid.pde index dc6daca58e..355777c598 100644 --- a/ArduCopter/control_hybrid.pde +++ b/ArduCopter/control_hybrid.pde @@ -26,7 +26,7 @@ // definitions that are independent of main loop rate #define HYBRID_STICK_RELEASE_SMOOTH_ANGLE 1800 // max angle required (in centi-degrees) after which the smooth stick release effect is applied #define HYBRID_WIND_COMP_START_TIMER 15 // delay (in 10zh increments) to start of wind compensation after loiter is engaged -#define HYBRID_WIND_COMP_ESTIMATE_SPEED_MAX 30 // wind compensation estimates will only run when velocity is at or below this speed in cm/s +#define HYBRID_WIND_COMP_ESTIMATE_SPEED_MAX 10 // wind compensation estimates will only run when velocity is at or below this speed in cm/s // declare some function to keep compiler happy static void hybrid_update_pilot_lean_angle(int16_t &lean_angle_filtered, int16_t &lean_angle_raw);