diff --git a/Rover/AP_Rally.cpp b/Rover/AP_Rally.cpp index 4680dda12f..1a83615964 100644 --- a/Rover/AP_Rally.cpp +++ b/Rover/AP_Rally.cpp @@ -21,7 +21,7 @@ bool AP_Rally_Rover::is_valid(const Location &rally_point) const { -#if AC_FENCE +#if AP_FENCE_ENABLED if (!rover.fence.check_destination_within_fence(rally_point)) { return false; } diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 542ee8ae23..e86e02ed85 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -843,7 +843,7 @@ void Rover::load_parameters(void) AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED); #endif -#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED | AC_FENCE +#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED | AP_FENCE_ENABLED // Find G2's Top Level Key AP_Param::ConversionInfo info; if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { @@ -864,7 +864,7 @@ void Rover::load_parameters(void) #endif // PARAMETER_CONVERSION - Added: Mar-2022 -#if AC_FENCE +#if AP_FENCE_ENABLED AP_Param::convert_class(info.old_key, &fence, fence.var_info, 17, 4049, false); #endif } diff --git a/Rover/fence.cpp b/Rover/fence.cpp index d541b92be7..fba0706bde 100644 --- a/Rover/fence.cpp +++ b/Rover/fence.cpp @@ -3,7 +3,7 @@ // fence_check - ask fence library to check for breaches and initiate the response void Rover::fence_check() { -#if AC_FENCE +#if AP_FENCE_ENABLED uint8_t new_breaches; // the type of fence that has been breached const uint8_t orig_breaches = fence.get_breaches(); @@ -57,5 +57,5 @@ void Rover::fence_check() AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } -#endif // AC_FENCE +#endif // AP_FENCE_ENABLED } diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 4900a02232..419209fc2a 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -481,7 +481,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) break; case MAV_CMD_DO_FENCE_ENABLE: -#if AC_FENCE +#if AP_FENCE_ENABLED if (cmd.p1 == 0) { //disable rover.fence.enable(false); gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled"); diff --git a/Rover/system.cpp b/Rover/system.cpp index eb5065798e..c6503ae7ee 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -220,7 +220,7 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason) control_mode = &new_mode; -#if AC_FENCE +#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