diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 07b06fc81b..3d4042e669 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -522,7 +522,6 @@ private: // sensors.cpp void init_compass(void); void compass_accumulate(void); - void init_barometer(bool full_calibration); void init_rangefinder(void); void init_beacon(); void init_visual_odom(); diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index eb6dc30050..30ff79debe 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -39,17 +39,6 @@ void Rover::compass_accumulate(void) } } -void Rover::init_barometer(bool full_calibration) -{ - gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer"); - if (full_calibration) { - barometer.calibrate(); - } else { - barometer.update_calibration(); - } - gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete"); -} - void Rover::init_rangefinder(void) { rangefinder.init(); diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 90b1b7179b..8e10de6ed1 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -103,7 +103,7 @@ void Rover::init_ardupilot() init_visual_odom(); // and baro for EKF - init_barometer(true); + barometer.calibrate(); // Do GPS init gps.set_log_gps_bit(MASK_LOG_GPS);