Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: change RTL_ALT_MIN from 200cm to 30cm #26449

Merged
merged 1 commit into from
Mar 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down