From 0219c85ee32b51be648f69e057cc50244aa20924 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 19 Nov 2013 16:46:16 +0900 Subject: [PATCH] Copter: increase min LAND_SPEED to 30cm/s --- ArduCopter/Parameters.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index e7c2fc10d5..d0f71184ad 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -226,7 +226,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @DisplayName: Land speed // @Description: The descent speed for the final stage of landing in cm/s // @Units: cm/s - // @Range: 20 200 + // @Range: 30 200 // @Increment: 10 // @User: Standard GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),