From 29785dabca8f5d1b63806b8ca4aaed5b9fcdf493 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 22 Oct 2021 08:42:55 +1100 Subject: [PATCH] Rover: use rangefinder distance() rather than distance_cm --- Rover/GCS_Mavlink.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 6ca3f6b11b..af76d74b8f 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -149,7 +149,7 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const void GCS_MAVLINK_Rover::send_rangefinder() const { - float distance_cm; + float distance; float voltage; bool got_one = false; @@ -160,8 +160,8 @@ void GCS_MAVLINK_Rover::send_rangefinder() const continue; } if (!got_one || - s->distance_cm() < distance_cm) { - distance_cm = s->distance_cm(); + s->distance() < distance) { + distance = s->distance(); voltage = s->voltage_mv(); got_one = true; } @@ -173,7 +173,7 @@ void GCS_MAVLINK_Rover::send_rangefinder() const mavlink_msg_rangefinder_send( chan, - distance_cm * 0.01f, + distance, voltage); }