diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 2bee51206b..d0d0c61c8c 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -899,7 +899,6 @@ private: int16_t get_throttle_mid(void); // sensors.cpp - void init_barometer(bool full_calibration); void read_barometer(void); void init_rangefinder(void); void read_rangefinder(void); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 6c734210b1..4c57dd5410 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -720,12 +720,6 @@ void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t* msg) MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) { - if (is_equal(packet.param3,1.0f)) { - // fast barometer calibration - copter.init_barometer(false); - return MAV_RESULT_ACCEPTED; - } - if (is_equal(packet.param6,1.0f)) { // compassmot calibration return copter.mavlink_compassmot(chan); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index a2739d6073..0ee0f6d0a2 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -1,16 +1,5 @@ #include "Copter.h" -void Copter::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"); -} - // return barometric altitude in centimeters void Copter::read_barometer(void) { diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index b7feb2353f..672db545af 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -209,7 +209,7 @@ void Copter::init_ardupilot() // read Baro pressure at ground //----------------------------- - init_barometer(true); + barometer.calibrate(); // initialise rangefinder init_rangefinder();