AC_Avoid: use proximity_avoidance_enabled function

This commit is contained in:
Tatsuya Yamaguchi 2021-08-01 21:21:01 +09:00 committed by Randy Mackay
parent 4044ea1a42
commit 7b77dd39e0
1 changed files with 2 additions and 2 deletions

View File

@ -194,7 +194,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa
float back_vel_down = 0.0f;
// Avoidance in response to proximity sensor
if ((_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) > 0 && _proximity_enabled && _proximity_alt_enabled) {
if (proximity_avoidance_enabled() && _proximity_alt_enabled) {
// Store velocity needed to back away from physical obstacles
Vector3f backup_vel_proximity;
adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel_cms, backup_vel_proximity, kP_z,accel_cmss_z, dt);
@ -421,7 +421,7 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c
void AC_Avoid::adjust_roll_pitch(float &roll, float &pitch, float veh_angle_max)
{
// exit immediately if proximity based avoidance is disabled
if ((_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) == 0 || !_proximity_enabled) {
if (!proximity_avoidance_enabled()) {
return;
}