mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: change AC_FENCE to AP_FENCE_ENABLED
This commit is contained in:
parent
1b160205ab
commit
a592f76282
|
@ -272,7 +272,7 @@ void Plane::update_logging2(void)
|
||||||
void Plane::afs_fs_check(void)
|
void Plane::afs_fs_check(void)
|
||||||
{
|
{
|
||||||
// perform AFS failsafe checks
|
// perform AFS failsafe checks
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
const bool fence_breached = fence.get_breaches() != 0;
|
const bool fence_breached = fence.get_breaches() != 0;
|
||||||
#else
|
#else
|
||||||
const bool fence_breached = false;
|
const bool fence_breached = false;
|
||||||
|
@ -344,7 +344,7 @@ void Plane::one_second_loop()
|
||||||
|
|
||||||
void Plane::three_hz_loop()
|
void Plane::three_hz_loop()
|
||||||
{
|
{
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
fence_check();
|
fence_check();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -65,7 +65,7 @@ bool Plane::stick_mixing_enabled(void)
|
||||||
// never stick mix without valid RC
|
// never stick mix without valid RC
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
const bool stickmixing = fence_stickmixing();
|
const bool stickmixing = fence_stickmixing();
|
||||||
#else
|
#else
|
||||||
const bool stickmixing = true;
|
const bool stickmixing = true;
|
||||||
|
|
|
@ -1385,7 +1385,7 @@ void Plane::load_parameters(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AC_FENCE
|
#if AP_FENCE_ENABLED
|
||||||
enum ap_var_type ptype_fence_type;
|
enum ap_var_type ptype_fence_type;
|
||||||
AP_Int8 *fence_type_new = (AP_Int8*)AP_Param::find("FENCE_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()) {
|
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
|
#if AP_TERRAIN_AVAILABLE
|
||||||
g.terrain_follow.convert_parameter_width(AP_PARAM_INT8);
|
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
|
#endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS
|
||||||
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2022
|
// 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);
|
AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, 0, true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -975,7 +975,7 @@ private:
|
||||||
void handle_battery_failsafe(const char* type_str, const int8_t action);
|
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.
|
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
|
// fence.cpp
|
||||||
void fence_check();
|
void fence_check();
|
||||||
bool fence_stickmixing() const;
|
bool fence_stickmixing() const;
|
||||||
|
|
|
@ -142,7 +142,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_FENCE_ENABLE:
|
case MAV_CMD_DO_FENCE_ENABLE:
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
if (cmd.p1 == 0) { // disable fence
|
if (cmd.p1 == 0) { // disable fence
|
||||||
plane.fence.enable(false);
|
plane.fence.enable(false);
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Fence disabled");
|
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);
|
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_LAND);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
plane.fence.auto_disable_fence_for_landing();
|
plane.fence.auto_disable_fence_for_landing();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -601,7 +601,7 @@ bool Plane::verify_takeoff()
|
||||||
auto_state.takeoff_complete = true;
|
auto_state.takeoff_complete = true;
|
||||||
next_WP_loc = prev_WP_loc = current_loc;
|
next_WP_loc = prev_WP_loc = current_loc;
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
plane.fence.auto_enable_fence_after_takeoff();
|
plane.fence.auto_enable_fence_after_takeoff();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -2,7 +2,7 @@
|
||||||
|
|
||||||
// Code to integrate AC_Fence library with main ArduPlane code
|
// 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
|
// fence_check - ask fence library to check for breaches and initiate the response
|
||||||
void Plane::fence_check()
|
void Plane::fence_check()
|
||||||
|
|
|
@ -16,7 +16,7 @@ bool ModeQLand::_enter()
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if LANDING_GEAR_ENABLED == ENABLED
|
||||||
plane.g2.landing_gear.deploy_for_landing();
|
plane.g2.landing_gear.deploy_for_landing();
|
||||||
#endif
|
#endif
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
plane.fence.auto_disable_fence_for_landing();
|
plane.fence.auto_disable_fence_for_landing();
|
||||||
#endif
|
#endif
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -114,7 +114,7 @@ void ModeTakeoff::update()
|
||||||
|
|
||||||
plane.set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_NORMAL);
|
plane.set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_NORMAL);
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
plane.fence.auto_enable_fence_after_takeoff();
|
plane.fence.auto_enable_fence_after_takeoff();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -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.
|
// todo: why are you doing this, I want to delete it.
|
||||||
set_alt_target_current();
|
set_alt_target_current();
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
plane.fence.auto_enable_fence_after_takeoff();
|
plane.fence.auto_enable_fence_after_takeoff();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -3271,7 +3271,7 @@ bool QuadPlane::verify_vtol_land(void)
|
||||||
poscontrol.pilot_correction_done = false;
|
poscontrol.pilot_correction_done = false;
|
||||||
pos_control->set_lean_angle_max_cd(0);
|
pos_control->set_lean_angle_max_cd(0);
|
||||||
poscontrol.xy_correction.zero();
|
poscontrol.xy_correction.zero();
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
plane.fence.auto_disable_fence_for_landing();
|
plane.fence.auto_disable_fence_for_landing();
|
||||||
#endif
|
#endif
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if LANDING_GEAR_ENABLED == ENABLED
|
||||||
|
|
|
@ -178,7 +178,7 @@ void Plane::read_radio()
|
||||||
|
|
||||||
control_failsafe();
|
control_failsafe();
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
const bool stickmixing = fence_stickmixing();
|
const bool stickmixing = fence_stickmixing();
|
||||||
#else
|
#else
|
||||||
const bool stickmixing = true;
|
const bool stickmixing = true;
|
||||||
|
|
Loading…
Reference in New Issue