GCS_MAVLink: adjust for proximity status namespace change

This commit is contained in:
Peter Barker 2019-09-27 18:59:41 +10:00 committed by Randy Mackay
parent ed720e73c1
commit 730257fe26
1 changed files with 1 additions and 1 deletions

View File

@ -342,7 +342,7 @@ void GCS_MAVLINK::send_proximity() const
const uint16_t dist_max = (uint16_t)(proximity->distance_max() * 100.0f); // maximum distance the sensor can measure in centimeters const uint16_t dist_max = (uint16_t)(proximity->distance_max() * 100.0f); // maximum distance the sensor can measure in centimeters
// send horizontal distances // send horizontal distances
if (proximity->get_status() == AP_Proximity::Proximity_Good) { if (proximity->get_status() == AP_Proximity::Status::Good) {
AP_Proximity::Proximity_Distance_Array dist_array; AP_Proximity::Proximity_Distance_Array dist_array;
if (proximity->get_horizontal_distances(dist_array)) { if (proximity->get_horizontal_distances(dist_array)) {
for (uint8_t i = 0; i < PROXIMITY_MAX_DIRECTION; i++) { for (uint8_t i = 0; i < PROXIMITY_MAX_DIRECTION; i++) {