AC_WPNav: move AC_Avoidance defines into libraries

This commit is contained in:
Peter Barker 2024-03-09 13:35:25 +11:00 committed by Peter Barker
parent 6e5ed88087
commit 84aaa8df63
4 changed files with 21 additions and 1 deletions

View File

@ -1,6 +1,7 @@
#include <AP_HAL/AP_HAL.h>
#include "AC_Loiter.h"
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AC_Avoidance/AC_Avoid.h>
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

View File

@ -1,3 +1,7 @@
#include "AC_WPNav_config.h"
#if AC_WPNAV_OA_ENABLED
#include <AP_Math/control.h>
#include <AP_InternalError/AP_InternalError.h>
#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

View File

@ -1,5 +1,9 @@
#pragma once
#include "AC_WPNav_config.h"
#if AC_WPNAV_OA_ENABLED
#include <AC_WPNav/AC_WPNav.h>
#include <AC_Avoidance/AP_OAPathPlanner.h>
#include <AC_Avoidance/AP_OABendyRuler.h>
@ -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

View File

@ -0,0 +1,7 @@
#pragma once
#include <AC_Avoidance/AC_Avoidance_config.h>
#ifndef AC_WPNAV_OA_ENABLED
#define AC_WPNAV_OA_ENABLED AP_OAPATHPLANNER_ENABLED
#endif