diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 653576f318..3cb9804c7e 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -244,7 +244,7 @@ void Sub::three_hz_loop() // check if we've lost terrain data failsafe_terrain_check(); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // check if we have breached a fence fence_check(); #endif // AP_FENCE_ENABLED diff --git a/ArduSub/control_guided.cpp b/ArduSub/control_guided.cpp index 0a444d9a08..851ff8fa90 100644 --- a/ArduSub/control_guided.cpp +++ b/ArduSub/control_guided.cpp @@ -129,7 +129,7 @@ bool Sub::guided_set_destination(const Vector3f& destination) guided_pos_control_start(); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!fence.check_destination_within_fence(dest_loc)) { @@ -157,7 +157,7 @@ bool Sub::guided_set_destination(const Location& dest_loc) guided_pos_control_start(); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination outside the fence. // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails if (!fence.check_destination_within_fence(dest_loc)) { @@ -201,7 +201,7 @@ bool Sub::guided_set_destination_posvel(const Vector3f& destination, const Vecto guided_posvel_control_start(); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!fence.check_destination_within_fence(dest_loc)) { diff --git a/ArduSub/fence.cpp b/ArduSub/fence.cpp index 56954855c4..7d89c89cae 100644 --- a/ArduSub/fence.cpp +++ b/ArduSub/fence.cpp @@ -2,7 +2,7 @@ // Code to integrate AC_Fence library with main ArduSub code -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // fence_check - ask fence library to check for breaches and initiate the response // called at 1hz diff --git a/ArduSub/flight_mode.cpp b/ArduSub/flight_mode.cpp index 2801d2cad8..cfd9c5943b 100644 --- a/ArduSub/flight_mode.cpp +++ b/ArduSub/flight_mode.cpp @@ -82,7 +82,7 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason) camera.set_is_auto_mode(control_mode == AUTO); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover // this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe) // but it should be harmless to disable the fence temporarily in these situations as well