#include "Copter.h"
void Copter::low_alt_avoidance()
{
#if AP_AVOIDANCE_ENABLED
float alt_m;
if (!get_rangefinder_height_interpolated_m(alt_m)) {
avoid.proximity_alt_avoidance_enable(true);
return;
}
bool enable_avoidance = true;
if (alt_m < avoid.get_min_alt()) {
enable_avoidance = false;
}
avoid.proximity_alt_avoidance_enable(enable_avoidance);
#endif
}