diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index de39d2235d..d2bb7e7263 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1347,7 +1347,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) result = MAV_RESULT_FAILED; } } else if (is_equal(packet.param3,1.0f)) { - plane.init_barometer(); + plane.init_barometer(false); if (plane.airspeed.enabled()) { plane.zero_airspeed(false); } diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index cd329b6c04..c54a0ed968 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -922,7 +922,7 @@ private: void trim_control_surfaces(); void trim_radio(); bool rc_failsafe_active(void); - void init_barometer(void); + void init_barometer(bool full_calibration); void init_rangefinder(void); void read_rangefinder(void); void read_airspeed(void); diff --git a/ArduPlane/sensors.cpp b/ArduPlane/sensors.cpp index 462292a515..e85e7644d6 100644 --- a/ArduPlane/sensors.cpp +++ b/ArduPlane/sensors.cpp @@ -3,11 +3,14 @@ #include "Plane.h" #include -void Plane::init_barometer(void) +void Plane::init_barometer(bool full_calibration) { gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer"); - barometer.calibrate(); - + if (full_calibration) { + barometer.calibrate(); + } else { + barometer.update_calibration(); + } gcs_send_text(MAV_SEVERITY_INFO, "Barometer calibration complete"); } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 05f1d3ecd5..748551bc55 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -617,7 +617,7 @@ void Plane::startup_INS_ground(void) // read Baro pressure at ground //----------------------------- - init_barometer(); + init_barometer(true); if (airspeed.enabled()) { // initialize airspeed sensor diff --git a/ArduPlane/test.cpp b/ArduPlane/test.cpp index 7d651907f7..84deb30f96 100644 --- a/ArduPlane/test.cpp +++ b/ArduPlane/test.cpp @@ -497,7 +497,7 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv) cliSerial->printf("Uncalibrated relative airpressure\n"); print_hit_enter(); - init_barometer(); + init_barometer(true); while(1) { hal.scheduler->delay(100);