TradHeli: dynamic flight check uses throttle in 0 to 1 range

This commit is contained in:
Leonard Hall 2016-01-02 12:16:34 +09:00 committed by Randy Mackay
parent d2a1cdf906
commit a0409e4f9e

View File

@ -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) {