diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index f909fcf43f..e843dd9ed2 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1177,7 +1177,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } if (packet.param3 == 1) { #if HIL_MODE != HIL_MODE_ATTITUDE - init_barometer(); + init_barometer(false); // fast barometer calibratoin #endif } if (packet.param4 == 1) { diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index d35796e336..4632b8c408 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -169,10 +169,8 @@ static void init_arm_motors() } #if HIL_MODE != HIL_MODE_ATTITUDE - // read Baro pressure at ground - - // this resets Baro for more accuracy - //----------------------------------- - init_barometer(); + // fast baro calibration to reset ground pressure + init_barometer(false); #endif // go back to normal AHRS gains diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index e580e02d61..839dc78c8d 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -14,10 +14,14 @@ static void init_sonar(void) } #endif -static void init_barometer(void) +static void init_barometer(bool full_calibration) { gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer")); - barometer.calibrate(); + if (full_calibration) { + barometer.calibrate(); + }else{ + barometer.update_calibration(); + } gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete")); } diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index f6022187d7..534d083b53 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -263,7 +263,7 @@ static void init_ardupilot() #if HIL_MODE != HIL_MODE_ATTITUDE // read Baro pressure at ground //----------------------------- - init_barometer(); + init_barometer(true); #endif // initialise sonar diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 6305d40b71..5b45c81675 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -64,7 +64,7 @@ test_baro(uint8_t argc, const Menu::arg *argv) { int32_t alt; print_hit_enter(); - init_barometer(); + init_barometer(true); while(1) { delay(100);