mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Use RTL_CLIMB_MIN in cone slope.
This commit is contained in:
parent
6d546eed8f
commit
e48b7cea12
@ -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
|
||||
|
@ -483,14 +483,14 @@ void ModeRTL::compute_return_target()
|
||||
int32_t target_alt = MAX(rtl_path.return_target.alt, 0);
|
||||
|
||||
// increase target to maximum of current altitude + climb_min and rtl altitude
|
||||
target_alt = MAX(target_alt, curr_alt + MAX(0, g.rtl_climb_min));
|
||||
target_alt = MAX(target_alt, MAX(g.rtl_altitude, RTL_ALT_MIN));
|
||||
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));
|
||||
|
||||
// reduce climb if close to 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, min_rtl_alt));
|
||||
}
|
||||
|
||||
// set returned target alt to new target_alt (don't change altitude type)
|
||||
|
Loading…
Reference in New Issue
Block a user