mirror of https://github.com/ArduPilot/ardupilot
Rover: tidy handling of barometer calibrations
This commit is contained in:
parent
05ee33d037
commit
c10f404b12
|
@ -522,7 +522,6 @@ private:
|
|||
// sensors.cpp
|
||||
void init_compass(void);
|
||||
void compass_accumulate(void);
|
||||
void init_barometer(bool full_calibration);
|
||||
void init_rangefinder(void);
|
||||
void init_beacon();
|
||||
void init_visual_odom();
|
||||
|
|
|
@ -39,17 +39,6 @@ void Rover::compass_accumulate(void)
|
|||
}
|
||||
}
|
||||
|
||||
void Rover::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 Rover::init_rangefinder(void)
|
||||
{
|
||||
rangefinder.init();
|
||||
|
|
|
@ -103,7 +103,7 @@ void Rover::init_ardupilot()
|
|||
init_visual_odom();
|
||||
|
||||
// and baro for EKF
|
||||
init_barometer(true);
|
||||
barometer.calibrate();
|
||||
|
||||
// Do GPS init
|
||||
gps.set_log_gps_bit(MASK_LOG_GPS);
|
||||
|
|
Loading…
Reference in New Issue