Skip to content

Commit

Permalink
Copter: Use RTL_CLIMB_MIN in cone slope.
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Nov 28, 2023
1 parent 11a5b78 commit f3caf78
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 5 deletions.
4 changes: 0 additions & 4 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -433,10 +433,6 @@
# define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL
#endif

#ifndef RTL_ABS_MIN_CLIMB
# define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb
#endif

#ifndef RTL_CONE_SLOPE_DEFAULT
# define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone
#endif
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -490,7 +490,7 @@ void ModeRTL::compute_return_target()
float rtl_return_dist_cm = rtl_path.return_target.get_distance(rtl_path.origin_point) * 100.0f;
// don't allow really shallow slopes
if (g.rtl_cone_slope >= RTL_MIN_CONE_SLOPE) {
target_alt = MAX(curr_alt, MIN(target_alt, MAX(rtl_return_dist_cm*g.rtl_cone_slope, curr_alt+RTL_ABS_MIN_CLIMB)));
target_alt = MIN(target_alt, MAX(rtl_return_dist_cm * g.rtl_cone_slope, curr_alt + MAX(0, g.rtl_climb_min)));
}

// set returned target alt to new target_alt (don't change altitude type)
Expand Down

0 comments on commit f3caf78

Please sign in to comment.