mirror of https://github.com/ArduPilot/ardupilot
Plane: don't stall EKF during baro cal
This commit is contained in:
parent
8c3bbdaf73
commit
d3494d1369
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -3,11 +3,14 @@
|
|||
#include "Plane.h"
|
||||
#include <AP_RSSI/AP_RSSI.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue