mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_WPNav: move AC_Avoidance defines into libraries
This commit is contained in:
parent
6e5ed88087
commit
84aaa8df63
@ -1,6 +1,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include "AC_Loiter.h"
|
#include "AC_Loiter.h"
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
|
#include <AC_Avoidance/AC_Avoid.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
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;
|
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) {
|
if (avoidance_on) {
|
||||||
// Limit the velocity to prevent fence violations
|
// Limit the velocity to prevent fence violations
|
||||||
// TODO: We need to also limit the _desired_accel
|
// TODO: We need to also limit the _desired_accel
|
||||||
|
@ -1,3 +1,7 @@
|
|||||||
|
#include "AC_WPNav_config.h"
|
||||||
|
|
||||||
|
#if AC_WPNAV_OA_ENABLED
|
||||||
|
|
||||||
#include <AP_Math/control.h>
|
#include <AP_Math/control.h>
|
||||||
#include <AP_InternalError/AP_InternalError.h>
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
#include "AC_WPNav_OA.h"
|
#include "AC_WPNav_OA.h"
|
||||||
@ -250,3 +254,5 @@ bool AC_WPNav_OA::update_wpnav()
|
|||||||
// run the non-OA update
|
// run the non-OA update
|
||||||
return AC_WPNav::update_wpnav();
|
return AC_WPNav::update_wpnav();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // Ac_WPNAV_OA_ENABLED
|
||||||
|
@ -1,5 +1,9 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AC_WPNav_config.h"
|
||||||
|
|
||||||
|
#if AC_WPNAV_OA_ENABLED
|
||||||
|
|
||||||
#include <AC_WPNav/AC_WPNav.h>
|
#include <AC_WPNav/AC_WPNav.h>
|
||||||
#include <AC_Avoidance/AP_OAPathPlanner.h>
|
#include <AC_Avoidance/AP_OAPathPlanner.h>
|
||||||
#include <AC_Avoidance/AP_OABendyRuler.h>
|
#include <AC_Avoidance/AP_OABendyRuler.h>
|
||||||
@ -45,3 +49,5 @@ protected:
|
|||||||
Location _oa_destination; // intermediate destination during avoidance
|
Location _oa_destination; // intermediate destination during avoidance
|
||||||
Location _oa_next_destination; // intermediate next destination during avoidance
|
Location _oa_next_destination; // intermediate next destination during avoidance
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AC_WPNAV_OA_ENABLED
|
||||||
|
7
libraries/AC_WPNav/AC_WPNav_config.h
Normal file
7
libraries/AC_WPNav/AC_WPNav_config.h
Normal 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
|
Loading…
Reference in New Issue
Block a user