mirror of https://github.com/ArduPilot/ardupilot
Copter: tidy handling of barometer calibrations
This commit is contained in:
parent
b862e4f3a8
commit
d58e2214d2
|
@ -899,7 +899,6 @@ private:
|
|||
int16_t get_throttle_mid(void);
|
||||
|
||||
// sensors.cpp
|
||||
void init_barometer(bool full_calibration);
|
||||
void read_barometer(void);
|
||||
void init_rangefinder(void);
|
||||
void read_rangefinder(void);
|
||||
|
|
|
@ -720,12 +720,6 @@ void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t* msg)
|
|||
|
||||
MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
{
|
||||
if (is_equal(packet.param3,1.0f)) {
|
||||
// fast barometer calibration
|
||||
copter.init_barometer(false);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
if (is_equal(packet.param6,1.0f)) {
|
||||
// compassmot calibration
|
||||
return copter.mavlink_compassmot(chan);
|
||||
|
|
|
@ -1,16 +1,5 @@
|
|||
#include "Copter.h"
|
||||
|
||||
void Copter::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");
|
||||
}
|
||||
|
||||
// return barometric altitude in centimeters
|
||||
void Copter::read_barometer(void)
|
||||
{
|
||||
|
|
|
@ -209,7 +209,7 @@ void Copter::init_ardupilot()
|
|||
|
||||
// read Baro pressure at ground
|
||||
//-----------------------------
|
||||
init_barometer(true);
|
||||
barometer.calibrate();
|
||||
|
||||
// initialise rangefinder
|
||||
init_rangefinder();
|
||||
|
|
Loading…
Reference in New Issue