AP_Proximity: change AC_FENCE to AP_FENCE_ENABLED

This commit is contained in:
Iampete1 2022-07-19 12:33:12 +01:00 committed by Andrew Tridgell
parent 94004db13f
commit ed330fd026

View File

@ -51,7 +51,7 @@ void AP_Proximity_SITL::update(void)
current_loc.lng = sitl->state.longitude * 1.0e7;
current_loc.alt = sitl->state.altitude * 1.0e2;
#if AC_FENCE
#if AP_FENCE_ENABLED
if (!AP::fence()->polyfence().breached()) {
// only called to prompt polyfence to reload fence if required
}
@ -81,7 +81,7 @@ void AP_Proximity_SITL::update(void)
// get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction)
bool AP_Proximity_SITL::get_distance_to_fence(float angle_deg, float &distance) const
{
#if AC_FENCE
#if AP_FENCE_ENABLED
if (!AP::fence()->polyfence().inclusion_boundary_available()) {
return false;
}