AC_Avoid: confirm USE_PROXIMITY_SENSOR to check if proximity is enabled

This commit is contained in:
Tatsuya Yamaguchi 2021-07-31 23:04:01 +09:00 committed by Randy Mackay
parent ebec8076c4
commit 4044ea1a42
2 changed files with 2 additions and 2 deletions

View File

@ -390,7 +390,7 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c
// get distance from proximity sensor
float proximity_alt_diff;
AP_Proximity *proximity = AP::proximity();
if (proximity && _proximity_enabled && proximity->get_upward_distance(proximity_alt_diff)) {
if (proximity && proximity_avoidance_enabled() && proximity->get_upward_distance(proximity_alt_diff)) {
proximity_alt_diff -= _margin;
if (!limit_alt || proximity_alt_diff < alt_diff) {
alt_diff = proximity_alt_diff;

View File

@ -81,7 +81,7 @@ public:
// enable/disable proximity based avoidance
void proximity_avoidance_enable(bool on_off) { _proximity_enabled = on_off; }
bool proximity_avoidance_enabled() const { return _proximity_enabled; }
bool proximity_avoidance_enabled() const { return (_proximity_enabled && (_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) > 0); }
void proximity_alt_avoidance_enable(bool on_off) { _proximity_alt_enabled = on_off; }
// helper functions