AC_Fence: replace location_offset() and get_distance() function calls with Location object member function calls

This allows removing duplicated code
This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2019-02-25 01:12:59 +01:00 committed by Peter Barker
parent edac5e1a80
commit f2ca3556cd
1 changed files with 1 additions and 1 deletions

View File

@ -379,7 +379,7 @@ bool AC_Fence::check_destination_within_fence(const Location& loc)
// Circular fence check // Circular fence check
if ((get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) { if ((get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {
if ((get_distance_cm(AP::ahrs().get_home(), loc) * 0.01f) > _circle_radius) { if (AP::ahrs().get_home().get_distance(loc) > _circle_radius) {
return false; return false;
} }
} }