From 0276c165eda731675396796a20df63f33f748e38 Mon Sep 17 00:00:00 2001 From: Sebastian Quilter Date: Mon, 18 Oct 2021 16:45:34 +1100 Subject: [PATCH] GCS_MAVLink: make rangefinder ranges m rather than cm --- libraries/GCS_MAVLink/GCS_Common.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 28b1b4efa7..a48a36cbdc 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -398,7 +398,7 @@ void GCS_MAVLINK::send_rangefinder() const } mavlink_msg_rangefinder_send( chan, - s->distance_cm() * 0.01f, + s->distance(), s->voltage_mv() * 0.001f); } @@ -4929,9 +4929,10 @@ void GCS_MAVLINK::send_water_depth() const ahrs.get_roll(), // roll in radians ahrs.get_pitch(), // pitch in radians ahrs.get_yaw(), // yaw in radians - s->distance_cm() * 0.01f, // distance in meters + s->distance(), // distance in meters temp_C); // temperature in degC } + #endif }