From 5aa54be718971a8d4cc3ec6870e450c65d86d38b Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <andrew@tridgell.net>
Date: Sat, 12 Sep 2015 18:34:25 +1000
Subject: [PATCH] GCS_MAVLink: send SCALED_PRESSURE3 for 3 baros

---
 libraries/GCS_MAVLink/GCS_Common.cpp | 11 +++++++++++
 1 file changed, 11 insertions(+)

diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp
index 47327c81cb..6ca564c558 100644
--- a/libraries/GCS_MAVLink/GCS_Common.cpp
+++ b/libraries/GCS_MAVLink/GCS_Common.cpp
@@ -1121,6 +1121,17 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
             barometer.get_temperature(1)*100); // 0.01 degrees C        
     }
 #endif
+#if BARO_MAX_INSTANCES > 2
+    if (barometer.num_instances() > 2) {
+        pressure = barometer.get_pressure(2);
+        mavlink_msg_scaled_pressure3_send(
+            chan,
+            now,
+            pressure*0.01f, // hectopascal
+            (pressure - barometer.get_ground_pressure(2))*0.01f, // hectopascal
+            barometer.get_temperature(2)*100); // 0.01 degrees C        
+    }
+#endif
 }
 
 void GCS_MAVLINK::send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer)