diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 8d4310a499..82c820fa82 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -272,7 +272,7 @@ void Plane::update_logging2(void) void Plane::afs_fs_check(void) { // perform AFS failsafe checks -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED const bool fence_breached = fence.get_breaches() != 0; #else const bool fence_breached = false; @@ -344,7 +344,7 @@ void Plane::one_second_loop() void Plane::three_hz_loop() { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED fence_check(); #endif } diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 77e80e61a8..63a3a3a239 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -65,7 +65,7 @@ bool Plane::stick_mixing_enabled(void) // never stick mix without valid RC return false; } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED const bool stickmixing = fence_stickmixing(); #else const bool stickmixing = true; diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index fffc5ed58e..03cd8a7991 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1385,7 +1385,7 @@ void Plane::load_parameters(void) } } -#if AC_FENCE +#if AP_FENCE_ENABLED enum ap_var_type ptype_fence_type; AP_Int8 *fence_type_new = (AP_Int8*)AP_Param::find("FENCE_TYPE", &ptype_fence_type); if (fence_type_new && !fence_type_new->configured()) { @@ -1470,7 +1470,7 @@ void Plane::load_parameters(void) } } } -#endif // AC_FENCE +#endif // AP_FENCE_ENABLED #if AP_TERRAIN_AVAILABLE g.terrain_follow.convert_parameter_width(AP_PARAM_INT8); @@ -1523,7 +1523,7 @@ void Plane::load_parameters(void) #endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS // PARAMETER_CONVERSION - Added: Mar-2022 -#if AC_FENCE +#if AP_FENCE_ENABLED AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, 0, true); #endif diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 3ddaa0aba0..85db9244ae 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -975,7 +975,7 @@ private: void handle_battery_failsafe(const char* type_str, const int8_t action); bool failsafe_in_landing_sequence() const; // returns true if the vehicle is in landing sequence. Intended only for use in failsafe code. -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // fence.cpp void fence_check(); bool fence_stickmixing() const; diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 0a5129d2ce..aa5c20058a 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -142,7 +142,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) break; case MAV_CMD_DO_FENCE_ENABLE: -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (cmd.p1 == 0) { // disable fence plane.fence.enable(false); gcs().send_text(MAV_SEVERITY_INFO, "Fence disabled"); @@ -418,7 +418,7 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd) set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_LAND); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_disable_fence_for_landing(); #endif } @@ -601,7 +601,7 @@ bool Plane::verify_takeoff() auto_state.takeoff_complete = true; next_WP_loc = prev_WP_loc = current_loc; -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_enable_fence_after_takeoff(); #endif diff --git a/ArduPlane/fence.cpp b/ArduPlane/fence.cpp index 99044f2748..a13dd64e0c 100644 --- a/ArduPlane/fence.cpp +++ b/ArduPlane/fence.cpp @@ -2,7 +2,7 @@ // Code to integrate AC_Fence library with main ArduPlane code -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // fence_check - ask fence library to check for breaches and initiate the response void Plane::fence_check() diff --git a/ArduPlane/mode_qland.cpp b/ArduPlane/mode_qland.cpp index dfc89ebfd9..204d90f036 100644 --- a/ArduPlane/mode_qland.cpp +++ b/ArduPlane/mode_qland.cpp @@ -16,7 +16,7 @@ bool ModeQLand::_enter() #if LANDING_GEAR_ENABLED == ENABLED plane.g2.landing_gear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_disable_fence_for_landing(); #endif return true; diff --git a/ArduPlane/mode_takeoff.cpp b/ArduPlane/mode_takeoff.cpp index d1eb42a4bc..3eb8604c37 100644 --- a/ArduPlane/mode_takeoff.cpp +++ b/ArduPlane/mode_takeoff.cpp @@ -114,7 +114,7 @@ void ModeTakeoff::update() plane.set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_NORMAL); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_enable_fence_after_takeoff(); #endif } diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 7046eb0add..9e0e75b59a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3139,7 +3139,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) // todo: why are you doing this, I want to delete it. set_alt_target_current(); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_enable_fence_after_takeoff(); #endif @@ -3271,7 +3271,7 @@ bool QuadPlane::verify_vtol_land(void) poscontrol.pilot_correction_done = false; pos_control->set_lean_angle_max_cd(0); poscontrol.xy_correction.zero(); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_disable_fence_for_landing(); #endif #if LANDING_GEAR_ENABLED == ENABLED diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 65c735e9fb..7cc32fb0ee 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -178,7 +178,7 @@ void Plane::read_radio() control_failsafe(); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED const bool stickmixing = fence_stickmixing(); #else const bool stickmixing = true;