mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_WPNav: don't link AC_Avoid on plane
saves about 7k of flash
This commit is contained in:
parent
88f4eb6017
commit
6e5bb1eb23
@ -1,5 +1,6 @@
|
|||||||
#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>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -274,6 +275,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, 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 (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
|
||||||
@ -284,6 +286,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on)
|
|||||||
desired_vel = Vector2f{avoidance_vel_3d.x, avoidance_vel_3d.y};
|
desired_vel = Vector2f{avoidance_vel_3d.x, avoidance_vel_3d.y};
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // !APM_BUILD_ArduPlane
|
||||||
|
|
||||||
// get loiters desired velocity from the position controller where it is being stored.
|
// get loiters desired velocity from the position controller where it is being stored.
|
||||||
Vector2p target_pos = _pos_control.get_pos_target_cm().xy();
|
Vector2p target_pos = _pos_control.get_pos_target_cm().xy();
|
||||||
|
Loading…
Reference in New Issue
Block a user