Copter: Refactor fence.get_safe_alt() to fence.get_safe_alt_max()

This commit is contained in:
Jacob Walser 2017-02-06 15:06:58 -05:00 committed by Andrew Tridgell
parent 5829d4b645
commit 868be023ee
1 changed files with 1 additions and 1 deletions

View File

@ -482,7 +482,7 @@ void Copter::rtl_compute_return_target(bool terrain_following_allowed)
if ((fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) {
// get return target as alt-above-home so it can be compared to fence's alt
if (rtl_path.return_target.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_HOME, target_alt)) {
float fence_alt = fence.get_safe_alt()*100.0f;
float fence_alt = fence.get_safe_alt_max()*100.0f;
if (target_alt > fence_alt) {
// reduce target alt to the fence alt
rtl_path.return_target.alt -= (target_alt - fence_alt);