From a0409e4f9e82c752b179e6f5537276fd5d609424 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sat, 2 Jan 2016 12:16:34 +0900 Subject: [PATCH] TradHeli: dynamic flight check uses throttle in 0 to 1 range --- ArduCopter/heli.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index e0eaac1a52..17c2d6fb76 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -54,7 +54,7 @@ void Copter::check_dynamic_flight(void) moving = (velocity >= HELI_DYNAMIC_FLIGHT_SPEED_MIN); }else{ // with no GPS lock base it on throttle and forward lean angle - moving = (motors.get_throttle() > 800.0f || ahrs.pitch_sensor < -1500); + moving = (motors.get_throttle() > 0.8f || ahrs.pitch_sensor < -1500); } if (!moving && sonar_enabled && sonar.status() == RangeFinder::RangeFinder_Good) {