mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Proximity: change AC_FENCE to AP_FENCE_ENABLED
This commit is contained in:
parent
94004db13f
commit
ed330fd026
@ -51,7 +51,7 @@ void AP_Proximity_SITL::update(void)
|
|||||||
current_loc.lng = sitl->state.longitude * 1.0e7;
|
current_loc.lng = sitl->state.longitude * 1.0e7;
|
||||||
current_loc.alt = sitl->state.altitude * 1.0e2;
|
current_loc.alt = sitl->state.altitude * 1.0e2;
|
||||||
|
|
||||||
#if AC_FENCE
|
#if AP_FENCE_ENABLED
|
||||||
if (!AP::fence()->polyfence().breached()) {
|
if (!AP::fence()->polyfence().breached()) {
|
||||||
// only called to prompt polyfence to reload fence if required
|
// 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)
|
// 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
|
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()) {
|
if (!AP::fence()->polyfence().inclusion_boundary_available()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user