diff --git a/ArduSub/APM_Config.h b/ArduSub/APM_Config.h index d88144366d..38c83e0713 100644 --- a/ArduSub/APM_Config.h +++ b/ArduSub/APM_Config.h @@ -35,7 +35,6 @@ // features below are disabled by default on all boards //#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity) -//#define GNDEFFECT_COMPENSATION ENABLED // enable ground effect compensation for barometer (if propwash interferes with the barometer on the ground) //#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link // other settings diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 43b6b8b805..531b8aa171 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -552,16 +552,6 @@ private: uint32_t last_pilot_yaw_input_ms; uint32_t fs_terrain_recover_start_ms = 0; -#if GNDEFFECT_COMPENSATION == ENABLED - // ground effect detector - struct { - bool takeoff_expected; - bool touchdown_expected; - uint32_t takeoff_time_ms; - float takeoff_alt_cm; - } gndeffect_state; -#endif // GNDEFFECT_COMPENSATION == ENABLED - static const AP_Scheduler::Task scheduler_tasks[]; static const AP_Param::Info var_info[]; static const struct LogStructure log_structure[]; @@ -856,9 +846,6 @@ private: void update_surface_and_bottom_detector(); void set_surfaced(bool at_surface); void set_bottomed(bool at_bottom); -#if GNDEFFECT_COMPENSATION == ENABLED - void update_ground_effect_detector(void); -#endif // GNDEFFECT_COMPENSATION == ENABLED void landinggear_update(); void update_notify(); void motor_test_output(); diff --git a/ArduSub/config.h b/ArduSub/config.h index 2091b8db4c..7facc07094 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -156,10 +156,6 @@ # define FS_GCS_TIMEOUT_MS 2500 // gcs failsafe triggers after 5 seconds with no GCS heartbeat #endif -#ifndef GNDEFFECT_COMPENSATION - # define GNDEFFECT_COMPENSATION DISABLED -#endif - // Radio failsafe while using RC_override #ifndef FS_RADIO_RC_OVERRIDE_TIMEOUT_MS # define FS_RADIO_RC_OVERRIDE_TIMEOUT_MS 1000 // RC Radio failsafe triggers after 1 second while using RC_override from ground station