From 65893cfca505d84585aa893e36d14b9afdf2b74a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 18 Mar 2018 15:22:12 +1100 Subject: [PATCH] Plane: tidy handling of barometer calibrations --- ArduPlane/GCS_Mavlink.cpp | 17 ++++++++++------- ArduPlane/GCS_Mavlink.h | 1 + ArduPlane/Plane.h | 1 - ArduPlane/sensors.cpp | 11 ----------- ArduPlane/system.cpp | 2 +- 5 files changed, 12 insertions(+), 20 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index e266890f45..652a3dc3b1 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -849,19 +849,22 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink return ret; } -MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration_baro() { - if (is_equal(packet.param3,1.0f)) { - /* - baro and airspeed calibration - */ - plane.init_barometer(false); + /* + baro and airspeed calibration + */ + MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro(); + if (ret == MAV_RESULT_ACCEPTED) { if (plane.airspeed.enabled()) { plane.zero_airspeed(false); } - return MAV_RESULT_ACCEPTED; } + return ret; +} +MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) +{ if (is_equal(packet.param4,1.0f)) { /* radio trim diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 2f05769bf5..6277491d07 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -33,6 +33,7 @@ protected: bool set_mode(uint8_t mode) override; + MAV_RESULT _handle_command_preflight_calibration_baro() override; MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet) override; MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 9869ded917..988b05e91a 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -926,7 +926,6 @@ private: void trim_control_surfaces(); void trim_radio(); bool rc_failsafe_active(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 8f70356fc8..0d519de436 100644 --- a/ArduPlane/sensors.cpp +++ b/ArduPlane/sensors.cpp @@ -1,17 +1,6 @@ #include "Plane.h" #include -void Plane::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 Plane::init_rangefinder(void) { rangefinder.init(); diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 545fac7a80..08ca2e392a 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -587,7 +587,7 @@ void Plane::startup_INS_ground(void) // read Baro pressure at ground //----------------------------- - init_barometer(true); + barometer.calibrate(); if (airspeed.enabled()) { // initialize airspeed sensor