diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index c1f9dbd892..aab6fa27f3 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -1,6 +1,7 @@ #include #include "AC_Loiter.h" #include +#include extern const AP_HAL::HAL& hal; @@ -265,7 +266,7 @@ void AC_Loiter::calc_desired_velocity(bool avoidance_on) desired_vel.y = desired_vel.y * gnd_speed_limit_cms / horizSpdDem; } -#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane) +#if AP_AVOIDANCE_ENABLED && !APM_BUILD_TYPE(APM_BUILD_ArduPlane) if (avoidance_on) { // Limit the velocity to prevent fence violations // TODO: We need to also limit the _desired_accel diff --git a/libraries/AC_WPNav/AC_WPNav_OA.cpp b/libraries/AC_WPNav/AC_WPNav_OA.cpp index b0ab5502b3..7b819fb7f3 100644 --- a/libraries/AC_WPNav/AC_WPNav_OA.cpp +++ b/libraries/AC_WPNav/AC_WPNav_OA.cpp @@ -1,3 +1,7 @@ +#include "AC_WPNav_config.h" + +#if AC_WPNAV_OA_ENABLED + #include #include #include "AC_WPNav_OA.h" @@ -250,3 +254,5 @@ bool AC_WPNav_OA::update_wpnav() // run the non-OA update return AC_WPNav::update_wpnav(); } + +#endif // Ac_WPNAV_OA_ENABLED diff --git a/libraries/AC_WPNav/AC_WPNav_OA.h b/libraries/AC_WPNav/AC_WPNav_OA.h index 2687c92552..67569d14f4 100644 --- a/libraries/AC_WPNav/AC_WPNav_OA.h +++ b/libraries/AC_WPNav/AC_WPNav_OA.h @@ -1,5 +1,9 @@ #pragma once +#include "AC_WPNav_config.h" + +#if AC_WPNAV_OA_ENABLED + #include #include #include @@ -45,3 +49,5 @@ protected: Location _oa_destination; // intermediate destination during avoidance Location _oa_next_destination; // intermediate next destination during avoidance }; + +#endif // AC_WPNAV_OA_ENABLED diff --git a/libraries/AC_WPNav/AC_WPNav_config.h b/libraries/AC_WPNav/AC_WPNav_config.h new file mode 100644 index 0000000000..9996acee9c --- /dev/null +++ b/libraries/AC_WPNav/AC_WPNav_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AC_WPNAV_OA_ENABLED +#define AC_WPNAV_OA_ENABLED AP_OAPATHPLANNER_ENABLED +#endif