|
|
@ -290,7 +290,7 @@ void GCS_MAVLINK::send_distance_sensor() const |
|
|
|
AP_Proximity *proximity = AP_Proximity::get_singleton(); |
|
|
|
AP_Proximity *proximity = AP_Proximity::get_singleton(); |
|
|
|
if (proximity != nullptr) { |
|
|
|
if (proximity != nullptr) { |
|
|
|
for (uint8_t i = 0; i < proximity->num_sensors(); i++) { |
|
|
|
for (uint8_t i = 0; i < proximity->num_sensors(); i++) { |
|
|
|
if (proximity->get_type(i) == AP_Proximity::Proximity_Type_RangeFinder) { |
|
|
|
if (proximity->get_type(i) == AP_Proximity::Type::RangeFinder) { |
|
|
|
filter_possible_proximity_sensors = true; |
|
|
|
filter_possible_proximity_sensors = true; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|