diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index f4ef3abe5b..267a3ea8a5 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -1,5 +1,7 @@ #include "AP_Avoidance.h" +#if HAL_ADSB_ENABLED + extern const AP_HAL::HAL& hal; #include @@ -680,3 +682,5 @@ AP_Avoidance *ap_avoidance() } } + +#endif // HAL_ADSB_ENABLED diff --git a/libraries/AP_Avoidance/AP_Avoidance.h b/libraries/AP_Avoidance/AP_Avoidance.h index a118092a27..d251aadf01 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.h +++ b/libraries/AP_Avoidance/AP_Avoidance.h @@ -27,6 +27,8 @@ #include +#if HAL_ADSB_ENABLED + #define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds) #define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds @@ -229,3 +231,6 @@ float closest_approach_z(const Location &my_loc, namespace AP { AP_Avoidance *ap_avoidance(); }; + +#endif +