diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 9bd3edb078..326210e22b 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -4,7 +4,7 @@ //#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space //#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space //#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash -//#define AC_FENCE DISABLED // disable fence to save 2k of flash +//#define AP_FENCE_ENABLED DISABLED // disable fence to save 2k of flash //#define CAMERA DISABLED // disable camera trigger to save 1k of flash //#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash //#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 0346ccf295..8845134bb0 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -331,7 +331,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) { // check if fence requires GPS bool fence_requires_gps = false; - #if AC_FENCE == ENABLED + #if AP_FENCE_ENABLED // if circular or polygon fence is enabled we need GPS fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0; #endif @@ -433,7 +433,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) // check if fence requires GPS bool fence_requires_gps = false; - #if AC_FENCE == ENABLED + #if AP_FENCE_ENABLED // if circular or polygon fence is enabled we need GPS fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0; #endif diff --git a/ArduCopter/AP_Rally.cpp b/ArduCopter/AP_Rally.cpp index 574a17d9f7..31027d7909 100644 --- a/ArduCopter/AP_Rally.cpp +++ b/ArduCopter/AP_Rally.cpp @@ -21,7 +21,7 @@ bool AP_Rally_Copter::is_valid(const Location &rally_point) const { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (!copter.fence.check_destination_within_fence(rally_point)) { return false; } diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 1565c7acac..d72af1add6 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -573,7 +573,7 @@ void Copter::three_hz_loop() // check for deadreckoning failsafe failsafe_deadreckon_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/ArduCopter/Copter.h b/ArduCopter/Copter.h index 287f3539f7..1d1c86c647 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -764,7 +764,7 @@ private: #endif // fence.cpp -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED void fence_check(); #endif diff --git a/ArduCopter/failsafe.cpp b/ArduCopter/failsafe.cpp index 75e44f36ec..d2d54a3afe 100644 --- a/ArduCopter/failsafe.cpp +++ b/ArduCopter/failsafe.cpp @@ -79,7 +79,7 @@ void Copter::failsafe_check() void Copter::afs_fs_check(void) { // perform AFS failsafe checks -#if AC_FENCE +#if AP_FENCE_ENABLED const bool fence_breached = fence.get_breaches() != 0; #else const bool fence_breached = false; diff --git a/ArduCopter/fence.cpp b/ArduCopter/fence.cpp index ab9164ed72..122d49a965 100644 --- a/ArduCopter/fence.cpp +++ b/ArduCopter/fence.cpp @@ -2,7 +2,7 @@ // Code to integrate AC_Fence library with main ArduCopter 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/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index ba1f506e2c..9e2083fc5d 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -312,7 +312,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) adsb.set_is_auto_mode((mode == Mode::Number::AUTO) || (mode == Mode::Number::RTL) || (mode == Mode::Number::GUIDED)); #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 diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 73e7b6f33e..cb70d526d4 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -408,7 +408,7 @@ void ModeAuto::land_start() copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif @@ -674,7 +674,7 @@ bool ModeAuto::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 copter.fence.enable(false); gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled"); @@ -682,7 +682,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) copter.fence.enable(true); gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled"); } -#endif //AC_FENCE == ENABLED +#endif //AP_FENCE_ENABLED break; #if NAV_GUIDED == ENABLED diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 0f4de592a5..f50b41be97 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -316,7 +316,7 @@ void ModeGuided::angle_control_start() // else return false if the waypoint is outside the fence bool ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool terrain_alt) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); if (!copter.fence.check_destination_within_fence(dest_loc)) { @@ -408,7 +408,7 @@ bool ModeGuided::get_wp(Location& destination) const // or if the fence is enabled and guided waypoint is outside the fence bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { -#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 (!copter.fence.check_destination_within_fence(dest_loc)) { @@ -551,7 +551,7 @@ bool ModeGuided::set_destination_posvel(const Vector3f& destination, const Vecto // set_destination_posvelaccel - set guided mode position, velocity and acceleration target bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const Vector3f& velocity, const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!copter.fence.check_destination_within_fence(dest_loc)) { diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 2f2c3f278a..8c518e5cec 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -41,7 +41,7 @@ bool ModeLand::init(bool ignore_checks) copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index fa1f2be64f..519b9759fb 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -284,7 +284,7 @@ void ModeRTL::descent_start() copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif @@ -382,7 +382,7 @@ void ModeRTL::land_start() copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif @@ -531,7 +531,7 @@ void ModeRTL::compute_return_target() // set returned target alt to new target_alt (don't change altitude type) rtl_path.return_target.set_alt_cm(target_alt, (alt_type == ReturnTargetAltType::RELATIVE) ? Location::AltFrame::ABOVE_HOME : Location::AltFrame::ABOVE_TERRAIN); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // ensure not above fence altitude if alt fence is enabled // Note: because the rtl_path.climb_target's altitude is simply copied from the return_target's altitude, // if terrain altitudes are being used, the code below which reduces the return_target's altitude can lead to diff --git a/ArduCopter/toy_mode.cpp b/ArduCopter/toy_mode.cpp index b80539f62e..922a51727b 100644 --- a/ArduCopter/toy_mode.cpp +++ b/ArduCopter/toy_mode.cpp @@ -430,7 +430,7 @@ void ToyMode::update() */ if (set_and_remember_mode(Mode::Number::ALT_HOLD, ModeReason::TOY_MODE)) { gcs().send_text(MAV_SEVERITY_INFO, "Tmode: ALT_HOLD update arm"); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(false); #endif if (!copter.arming.arm(AP_Arming::Method::MAVLINK)) { @@ -459,7 +459,7 @@ void ToyMode::update() AP_Notify::flags.hybrid_loiter = false; #endif } else if (copter.position_ok() && set_and_remember_mode(Mode::Number::LOITER, ModeReason::TOY_MODE)) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(true); #endif gcs().send_text(MAV_SEVERITY_INFO, "Tmode: LOITER update"); @@ -622,7 +622,7 @@ void ToyMode::update() copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::TOY_MODE); } else { copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::TOY_MODE); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(false); #endif if (copter.arming.arm(AP_Arming::Method::MAVLINK)) { @@ -643,13 +643,13 @@ void ToyMode::update() if (new_mode != copter.flightmode->mode_number()) { load_test.running = false; -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(false); #endif if (set_and_remember_mode(new_mode, ModeReason::TOY_MODE)) { gcs().send_text(MAV_SEVERITY_INFO, "Tmode: mode %s", copter.flightmode->name4()); // force fence on in all GPS flight modes -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (copter.flightmode->requires_GPS()) { copter.fence.enable(true); } @@ -660,7 +660,7 @@ void ToyMode::update() // if we can't RTL then land gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: LANDING"); set_and_remember_mode(Mode::Number::LAND, ModeReason::TOY_MODE); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (copter.landing_with_GPS()) { copter.fence.enable(true); } @@ -799,7 +799,7 @@ void ToyMode::action_arm(void) arm_check_compass(); if (needs_gps && copter.arming.gps_checks(false)) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // we want GPS and checks are passing, arm and enable fence copter.fence.enable(true); #endif @@ -815,7 +815,7 @@ void ToyMode::action_arm(void) AP_Notify::events.arming_failed = true; gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: GPS arming failed"); } else { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // non-GPS mode copter.fence.enable(false); #endif