mirror of https://github.com/ArduPilot/ardupilot
AC_Avoid: confirm USE_PROXIMITY_SENSOR to check if proximity is enabled
This commit is contained in:
parent
19a9e1a416
commit
04deabbacb
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue