Skip to content

Commit

Permalink
ArduPlane: change AC_FENCE to AP_FENCE_ENABLED
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Jul 27, 2022
1 parent 1b16020 commit a592f76
Show file tree
Hide file tree
Showing 10 changed files with 16 additions and 16 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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
}
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()) {
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -975,7 +975,7 @@ class Plane : public AP_Vehicle {
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;
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
Expand Down Expand Up @@ -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
}
Expand Down Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_qland.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit a592f76

Please sign in to comment.