Rover: don't stall EKF during baro cal
This commit is contained in:
parent
1581a5e354
commit
f61ba903dd
@ -942,7 +942,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
result = MAV_RESULT_FAILED;
|
||||
}
|
||||
} else if (is_equal(packet.param3,1.0f)) {
|
||||
rover.init_barometer();
|
||||
rover.init_barometer(false);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else if (is_equal(packet.param4,1.0f)) {
|
||||
rover.trim_radio();
|
||||
|
@ -464,7 +464,7 @@ private:
|
||||
bool throttle_failsafe_active();
|
||||
void trim_control_surfaces();
|
||||
void trim_radio();
|
||||
void init_barometer(void);
|
||||
void init_barometer(bool full_calibration);
|
||||
void init_sonar(void);
|
||||
void read_battery(void);
|
||||
void read_receiver_rssi(void);
|
||||
|
@ -2,10 +2,14 @@
|
||||
|
||||
#include "Rover.h"
|
||||
|
||||
void Rover::init_barometer(void)
|
||||
void Rover::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");
|
||||
}
|
||||
|
||||
|
@ -149,7 +149,7 @@ void Rover::init_ardupilot()
|
||||
init_sonar();
|
||||
|
||||
// and baro for EKF
|
||||
init_barometer();
|
||||
init_barometer(true);
|
||||
|
||||
// Do GPS init
|
||||
gps.init(&DataFlash, serial_manager);
|
||||
|
Loading…
Reference in New Issue
Block a user