From 481a55867e1b0e6f2cd6c196feea03984856e832 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Fri, 16 May 2014 14:45:39 +0900
Subject: [PATCH] Copter: only send sonar distance to GCS when sonar enabled

---
 ArduCopter/GCS_Mavlink.pde | 4 ++++
 1 file changed, 4 insertions(+)

diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde
index 7b665eb4d..cb795c3fd 100644
--- a/ArduCopter/GCS_Mavlink.pde
+++ b/ArduCopter/GCS_Mavlink.pde
@@ -581,6 +581,10 @@ static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
 #if CONFIG_SONAR == ENABLED
 static void NOINLINE send_rangefinder(mavlink_channel_t chan)
 {
+    // exit immediately if sonar is disabled
+    if (!g.sonar_enabled) {
+        return;
+    }
     mavlink_msg_rangefinder_send(chan, sonar_alt * 0.01f, 0);
 }
 #endif
-- 
GitLab