mirror of https://github.com/ArduPilot/ardupilot
AC_Avoid: use proximity_avoidance_enabled function
This commit is contained in:
parent
04deabbacb
commit
43da962d34
|
@ -194,7 +194,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa
|
||||||
float back_vel_down = 0.0f;
|
float back_vel_down = 0.0f;
|
||||||
|
|
||||||
// Avoidance in response to proximity sensor
|
// 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
|
// Store velocity needed to back away from physical obstacles
|
||||||
Vector3f backup_vel_proximity;
|
Vector3f backup_vel_proximity;
|
||||||
adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel_cms, backup_vel_proximity, kP_z,accel_cmss_z, dt);
|
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)
|
void AC_Avoid::adjust_roll_pitch(float &roll, float &pitch, float veh_angle_max)
|
||||||
{
|
{
|
||||||
// exit immediately if proximity based avoidance is disabled
|
// exit immediately if proximity based avoidance is disabled
|
||||||
if ((_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) == 0 || !_proximity_enabled) {
|
if (!proximity_avoidance_enabled()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue