Sub: Only save baro calibration parameters when user zeros

This commit is contained in:
Jacob Walser 2017-02-10 10:58:57 -05:00 committed by Andrew Tridgell
parent 942d6450d2
commit 65cd28cc6c
4 changed files with 7 additions and 13 deletions

View File

@ -1320,7 +1320,7 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
if (!sub.ap.depth_sensor_present || sub.motors.armed() || sub.barometer.get_pressure() > 110000) { if (!sub.ap.depth_sensor_present || sub.motors.armed() || sub.barometer.get_pressure() > 110000) {
result = MAV_RESULT_FAILED; result = MAV_RESULT_FAILED;
} else { } else {
sub.init_barometer(false); sub.init_barometer(true);
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
} }
} else if (is_equal(packet.param4,1.0f)) { } else if (is_equal(packet.param4,1.0f)) {

View File

@ -767,7 +767,7 @@ private:
void default_js_buttons(void); void default_js_buttons(void);
void set_throttle_zero_flag(int16_t throttle_control); void set_throttle_zero_flag(int16_t throttle_control);
void radio_passthrough_to_motors(); void radio_passthrough_to_motors();
void init_barometer(bool full_calibration); void init_barometer(bool save);
void read_barometer(void); void read_barometer(void);
void init_rangefinder(void); void init_rangefinder(void);
void read_rangefinder(void); void read_rangefinder(void);

View File

@ -1,13 +1,9 @@
#include "Sub.h" #include "Sub.h"
void Sub::init_barometer(bool full_calibration) void Sub::init_barometer(bool save)
{ {
gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer"); gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
if (full_calibration) { barometer.calibrate(save);
barometer.calibrate();
} else {
barometer.update_calibration();
}
gcs_send_text(MAV_SEVERITY_INFO, "Barometer calibration complete"); gcs_send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
} }

View File

@ -229,7 +229,9 @@ void Sub::init_ardupilot()
ins.set_hil_mode(); ins.set_hil_mode();
#endif #endif
barometer.calibrate(); // read Baro pressure at ground
//-----------------------------
init_barometer(false);
barometer.update(); barometer.update();
if (barometer.healthy(1)) { // We have an external MS58XX pressure sensor connected if (barometer.healthy(1)) { // We have an external MS58XX pressure sensor connected
@ -247,10 +249,6 @@ void Sub::init_ardupilot()
leak_detector.init(); leak_detector.init();
// read Baro pressure at ground
//-----------------------------
init_barometer(true);
// backwards compatibility // backwards compatibility
if (attitude_control.get_accel_yaw_max() < 110000.0f) { if (attitude_control.get_accel_yaw_max() < 110000.0f) {
attitude_control.save_accel_yaw_max(110000.0f); attitude_control.save_accel_yaw_max(110000.0f);