From 59d1f225d5f17fb7f7d7de27e79723b1bf58f089 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 21 Jan 2012 22:06:35 -0800 Subject: [PATCH] convert command into CM from M Making Landing boost be one at minimum to trigger better navthrottle output --- ArduCopter/commands_logic.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 74ce2488de..d8bd2bbd36 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -365,7 +365,7 @@ static bool verify_land() //landing_boost = min(landing_boost, 15); float tmp = (1.75 * icount * icount) - (7.2 * icount); landing_boost = tmp; - landing_boost = constrain(landing_boost, 0, 200); + landing_boost = constrain(landing_boost, 1, 200); icount += 0.4; //Serial.printf("lb:%d, %1.4f, ic:%1.4f\n",landing_boost, tmp, icount); @@ -512,7 +512,7 @@ static void do_change_alt() static void do_within_distance() { - condition_value = command_cond_queue.lat; + condition_value = command_cond_queue.lat * 100; } static void do_yaw()