From 2d29698df86327142c6f4612ede4ce8c296e3471 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Mon, 6 Feb 2017 17:06:33 -0500 Subject: [PATCH] Sub: Use AP_Baro::baro_type_t --- ArduSub/system.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 11ba0c5bba..bf1c9b70d9 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -239,7 +239,7 @@ void Sub::init_ardupilot() ap.depth_sensor_present = true; for (int i = 1; i < barometer.num_instances(); i++) { - barometer.set_type(i, BARO_TYPE_WATER); // Altitude (depth) is calculated differently underwater + barometer.set_type(i, AP_Baro::BARO_TYPE_WATER); // Altitude (depth) is calculated differently underwater barometer.set_precision_multiplier(i, 40); // The MS58XX values reported need to be multiplied by 10 to match units everywhere else } @@ -254,7 +254,7 @@ void Sub::init_ardupilot() ap.depth_sensor_present = false; for (int i = 1; i < barometer.num_instances(); i++) { - barometer.set_type(i, BARO_TYPE_AIR); // Default fcu air baro + barometer.set_type(i, AP_Baro::BARO_TYPE_AIR); // Default fcu air baro barometer.set_precision_multiplier(i, 1); // Use default values } EKF2.set_baro_alt_noise(10.0f); // Readings won't correspond with rest of INS