From 251db3f414fcbbe9da6619c637366070e8c69d98 Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Fri, 8 Mar 2024 11:05:01 +0900 Subject: [PATCH] Copter: change RTL_ALT_MIN from 200cm to 30cm --- ArduCopter/Parameters.cpp | 2 +- ArduCopter/config.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 5eb636d938..d999b836da 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -102,7 +102,7 @@ const AP_Param::Info Copter::var_info[] = { // @DisplayName: RTL Altitude // @Description: The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude. // @Units: cm - // @Range: 200 300000 + // @Range: 30 300000 // @Increment: 1 // @User: Standard GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT), diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 9851032591..bd139ff23a 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -434,7 +434,7 @@ #endif #ifndef RTL_ALT_MIN - # define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m) + # define RTL_ALT_MIN 30 // min height above ground for RTL (i.e 30cm) #endif #ifndef RTL_CLIMB_MIN_DEFAULT