Skip to content

Commit

Permalink
Copter: change RTL_ALT_MIN from 200cm to 30cm
Browse files Browse the repository at this point in the history
  • Loading branch information
tatsuy committed Mar 7, 2024
1 parent d911475 commit 809c168
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 5 deletions.
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
6 changes: 5 additions & 1 deletion ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -429,8 +429,12 @@
# define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude
#endif

#ifndef RTL_ALT_LOW
# define RTL_ALT_LOW 200 // Height used when RTL_ALT is set to a value lower than RTL_ALT_MIN
#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
7 changes: 4 additions & 3 deletions ArduCopter/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -443,8 +443,9 @@ void ModeRTL::compute_return_target()
// set curr_alt and return_target.alt from range finder
if (alt_type == ReturnTargetAltType::RANGEFINDER) {
if (copter.get_rangefinder_height_interpolated_cm(curr_alt)) {
int32_t min_rtl_alt = g.rtl_altitude >= RTL_ALT_MIN ? g.rtl_altitude : RTL_ALT_LOW;
// set return_target.alt
rtl_path.return_target.set_alt_cm(MAX(curr_alt + MAX(0, g.rtl_climb_min), MAX(g.rtl_altitude, RTL_ALT_MIN)), Location::AltFrame::ABOVE_TERRAIN);
rtl_path.return_target.set_alt_cm(MAX(curr_alt + MAX(0, g.rtl_climb_min), min_rtl_alt), Location::AltFrame::ABOVE_TERRAIN);
} else {
// fallback to relative alt and warn user
alt_type = ReturnTargetAltType::RELATIVE;
Expand Down Expand Up @@ -484,9 +485,9 @@ void ModeRTL::compute_return_target()
// Note: ignore negative altitudes which could happen if user enters negative altitude for rally point or terrain is higher at rally point compared to home
int32_t target_alt = MAX(rtl_path.return_target.alt, 0);

const int32_t min_rtl_alt = g.rtl_altitude < RTL_ALT_MIN ? RTL_ALT_LOW : g.rtl_altitude;
// increase target to maximum of current altitude + climb_min and rtl altitude
const float min_rtl_alt = MAX(RTL_ALT_MIN, curr_alt + MAX(0, g.rtl_climb_min));
target_alt = MAX(target_alt, MAX(g.rtl_altitude, min_rtl_alt));
target_alt = MAX(target_alt, MAX(min_rtl_alt, curr_alt + MAX(0, g.rtl_climb_min)));

// reduce climb if close to return target
float rtl_return_dist_cm = rtl_path.return_target.get_distance(rtl_path.origin_point) * 100.0f;
Expand Down

0 comments on commit 809c168

Please sign in to comment.