diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 77ec952ac3..a728d91657 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -31,7 +31,6 @@ //#define MODE_THROW_ENABLED DISABLED // disable throw mode support //#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support //#define OSD_ENABLED DISABLED // disable on-screen-display support -//#define LANDING_GEAR_ENABLED DISABLED // disable landing gear support // features below are disabled by default on all boards //#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index e91d725c21..94ae6a0c33 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -193,7 +193,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(check_vibration, 10, 50, 87), SCHED_TASK(gpsglitch_check, 10, 50, 90), SCHED_TASK(takeoff_check, 50, 50, 91), -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED SCHED_TASK(landinggear_update, 10, 75, 93), #endif SCHED_TASK(standby_update, 100, 75, 96), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 180e9d75fd..69c2512ac2 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -516,7 +516,7 @@ private: #endif // Landing Gear Controller -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED AP_LandingGear landinggear; #endif @@ -804,7 +804,7 @@ private: void set_land_complete_maybe(bool b); void update_throttle_mix(); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // landing_gear.cpp void landinggear_update(); #endif diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index e6c12cc7cf..91d47aa481 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -920,7 +920,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ return MAV_RESULT_FAILED; #endif -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED case MAV_CMD_AIRFRAME_CONFIGURATION: { // Param 1: Select which gear, not used in ArduPilot // Param 2: 0 = Deploy, 1 = Retract diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index ada7885150..f6f79de94b 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -472,7 +472,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(parachute, "CHUTE_", AP_Parachute), #endif -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // @Group: LGR_ // @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp GOBJECT(landinggear, "LGR_", AP_LandingGear), @@ -1292,7 +1292,7 @@ void Copter::load_parameters(void) AP_Param::load_all(); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // convert landing gear parameters // PARAMETER_CONVERSION - Added: Nov-2018 convert_lgr_parameters(); @@ -1559,7 +1559,7 @@ void Copter::convert_prx_parameters() } #endif -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED /* convert landing gear parameters */ diff --git a/ArduCopter/config.h b/ArduCopter/config.h index b1e96c2c37..cab0948ba5 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -298,12 +298,6 @@ # define BEACON_ENABLED !HAL_MINIMIZE_FEATURES #endif -////////////////////////////////////////////////////////////////////////////// -// Landing Gear support -#ifndef LANDING_GEAR_ENABLED - #define LANDING_GEAR_ENABLED ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // RADIO CONFIGURATION ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 2b2c0e5a12..18a04aec4f 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -337,7 +337,7 @@ void Copter::parachute_release() // release parachute parachute.release(); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // deploy landing gear landinggear.set_position(AP_LandingGear::LandingGear_Deploy); #endif diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index 94f1df5541..69b65b88dc 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -88,7 +88,7 @@ void Copter::update_land_detector() #endif uint8_t land_detector_scalar = 1; -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED if (landinggear.get_wow_state() != AP_LandingGear::LG_WOW_UNKNOWN) { // we have a WoW sensor so lets loosen the strictness of the landing detector land_detector_scalar = 2; @@ -105,7 +105,7 @@ void Copter::update_land_detector() bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM); // if we have weight on wheels (WoW) or ambiguous unknown. never no WoW -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED const bool WoW_check = (landinggear.get_wow_state() == AP_LandingGear::LG_WOW || landinggear.get_wow_state() == AP_LandingGear::LG_WOW_UNKNOWN); #else const bool WoW_check = true; diff --git a/ArduCopter/landing_gear.cpp b/ArduCopter/landing_gear.cpp index c93657df55..2aec67d2b2 100644 --- a/ArduCopter/landing_gear.cpp +++ b/ArduCopter/landing_gear.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // Run landing gear controller at 10Hz void Copter::landinggear_update() @@ -35,4 +35,4 @@ void Copter::landinggear_update() landinggear.update(height_cm * 0.01f); // convert cm->m for update call } -#endif // LANDING_GEAR_ENABLED +#endif // AP_LANDINGGEAR_ENABLED diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index ea66cbf9de..7049646af5 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -405,7 +405,7 @@ void ModeAuto::land_start() // initialise yaw auto_yaw.set_mode(AutoYaw::Mode::HOLD); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // optionally deploy landing gear copter.landinggear.deploy_for_landing(); #endif @@ -1785,7 +1785,7 @@ void ModeAuto::do_RTL(void) // verify_takeoff - check if we have completed the takeoff bool ModeAuto::verify_takeoff() { -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // if we have reached our destination if (auto_takeoff_complete) { // retract the landing gear diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 7aa583f016..3b37e20b28 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -652,7 +652,7 @@ void ModeGuided::takeoff_run() auto_takeoff_run(); if (auto_takeoff_complete && !takeoff_complete) { takeoff_complete = true; -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // optionally retract landing gear copter.landinggear.retract_after_takeoff(); #endif diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index b81b97af80..4072e76c8b 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -36,7 +36,7 @@ bool ModeLand::init(bool ignore_checks) // initialise yaw auto_yaw.set_mode(AutoYaw::Mode::HOLD); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // optionally deploy landing gear copter.landinggear.deploy_for_landing(); #endif diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 30fdf9af58..4718bd7421 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -247,7 +247,7 @@ void ModeRTL::descent_start() // initialise yaw auto_yaw.set_mode(AutoYaw::Mode::HOLD); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // optionally deploy landing gear copter.landinggear.deploy_for_landing(); #endif @@ -339,7 +339,7 @@ void ModeRTL::land_start() // initialise yaw auto_yaw.set_mode(AutoYaw::Mode::HOLD); -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // optionally deploy landing gear copter.landinggear.deploy_for_landing(); #endif diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index eaa74c838f..8b05c78caf 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -132,7 +132,7 @@ void Copter::init_ardupilot() init_precland(); #endif -#if LANDING_GEAR_ENABLED == ENABLED +#if AP_LANDINGGEAR_ENABLED // initialise landing gear position landinggear.init(); #endif