3 // check if proximity type Simple Avoidance should be enabled based on alt
4 void Copter::low_alt_avoidance()
6 #if AP_AVOIDANCE_ENABLED
8 if (!get_rangefinder_height_interpolated_cm(alt_cm
)) {
9 // enable avoidance if we don't have a valid rangefinder reading
10 avoid
.proximity_alt_avoidance_enable(true);
14 bool enable_avoidance
= true;
15 if (alt_cm
< avoid
.get_min_alt() * 100.0f
) {
16 enable_avoidance
= false;
18 avoid
.proximity_alt_avoidance_enable(enable_avoidance
);