diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 852b9bcaa8..e69f7abe2b 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -133,7 +133,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { #if AP_GRIPPER_ENABLED SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75, 156), #endif -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED SCHED_TASK(landing_gear_update, 5, 50, 159), #endif }; diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 46edac2a95..b760e0b2fe 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1096,7 +1096,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1), -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // @Group: LGR_ // @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear), diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 1164377929..7c429cd5a1 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -528,7 +528,7 @@ public: AP_Int8 takeoff_throttle_accel_count; AP_Int8 takeoff_timeout; -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED AP_LandingGear landing_gear; #endif diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 005ef28af1..20817c96d4 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -558,7 +558,7 @@ private: #endif // OFFBOARD_GUIDED == ENABLED } guided_state; -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // landing gear state struct { AP_FixedWing::FlightStage last_flight_stage; diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 1530e40c06..0bc95aa615 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -250,10 +250,6 @@ #define OFFBOARD_GUIDED !HAL_MINIMIZE_FEATURES #endif -#ifndef LANDING_GEAR_ENABLED - #define LANDING_GEAR_ENABLED !HAL_MINIMIZE_FEATURES -#endif - ////////////////////////////////////////////////////////////////////////////// // EKF Failsafe #ifndef FS_EKF_THRESHOLD_DEFAULT diff --git a/ArduPlane/mode_qland.cpp b/ArduPlane/mode_qland.cpp index 204d90f036..e646c80746 100644 --- a/ArduPlane/mode_qland.cpp +++ b/ArduPlane/mode_qland.cpp @@ -13,7 +13,7 @@ bool ModeQLand::_enter() quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing); quadplane.landing_detect.lower_limit_start_ms = 0; quadplane.landing_detect.land_start_ms = 0; -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED plane.g2.landing_gear.deploy_for_landing(); #endif #if AP_FENCE_ENABLED diff --git a/ArduPlane/parachute.cpp b/ArduPlane/parachute.cpp index 001a134ef4..61cec7ae0a 100644 --- a/ArduPlane/parachute.cpp +++ b/ArduPlane/parachute.cpp @@ -31,7 +31,7 @@ void Plane::parachute_release() // release parachute parachute.release(); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // deploy landing gear g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy); #endif @@ -59,10 +59,10 @@ bool Plane::parachute_manual_release() // if we get this far release parachute parachute_release(); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // deploy landing gear g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy); #endif return true; } -#endif \ No newline at end of file +#endif diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 452b15f696..0211be18e8 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3325,7 +3325,7 @@ bool QuadPlane::verify_vtol_land(void) #if AP_FENCE_ENABLED plane.fence.auto_disable_fence_for_landing(); #endif -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED plane.g2.landing_gear.deploy_for_landing(); #endif last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing); diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 821a8026a5..c550d3aba7 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -691,7 +691,7 @@ void Plane::set_servos_flaps(void) flaperon_update(); } -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED /* setup landing gear state */ @@ -711,7 +711,7 @@ void Plane::set_landing_gear(void) } gear.last_flight_stage = flight_stage; } -#endif // LANDING_GEAR_ENABLED +#endif // AP_LANDINGGEAR_ENABLED /* @@ -879,7 +879,7 @@ void Plane::set_servos(void) // setup flap outputs set_servos_flaps(); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // setup landing gear output set_landing_gear(); #endif diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index c0ab5b1110..1bbad62b5f 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -101,7 +101,7 @@ void Plane::init_ardupilot() camera_mount.init(); #endif -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // initialise landing gear position g2.landing_gear.init(); #endif diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index ad2c544134..0f0ee7f7df 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -274,7 +274,7 @@ return_zero: return 0; } -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED /* update landing gear */