From 36150348bbf39c30de5db0a3388b50ac3fb3e503 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Wed, 14 Oct 2015 12:57:21 -0300 Subject: [PATCH] GCS_MAVLink: remove check for max BARO instances For all supported boards we allow more than 1 baro instance. --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index b6b247abb2..0dcc835bac 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1121,7 +1121,7 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer) pressure*0.01f, // hectopascal (pressure - barometer.get_ground_pressure(0))*0.01f, // hectopascal barometer.get_temperature(0)*100); // 0.01 degrees C -#if BARO_MAX_INSTANCES > 1 + if (barometer.num_instances() > 1) { pressure = barometer.get_pressure(1); mavlink_msg_scaled_pressure2_send( @@ -1131,8 +1131,7 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer) (pressure - barometer.get_ground_pressure(1))*0.01f, // hectopascal 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( @@ -1142,7 +1141,6 @@ void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer) (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)