mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: tidy handling of barometer calibrations
This commit is contained in:
parent
c10f404b12
commit
65893cfca5
@ -849,19 +849,22 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink
|
||||
return ret;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration_baro()
|
||||
{
|
||||
if (is_equal(packet.param3,1.0f)) {
|
||||
/*
|
||||
baro and airspeed calibration
|
||||
*/
|
||||
plane.init_barometer(false);
|
||||
/*
|
||||
baro and airspeed calibration
|
||||
*/
|
||||
MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro();
|
||||
if (ret == MAV_RESULT_ACCEPTED) {
|
||||
if (plane.airspeed.enabled()) {
|
||||
plane.zero_airspeed(false);
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
{
|
||||
if (is_equal(packet.param4,1.0f)) {
|
||||
/*
|
||||
radio trim
|
||||
|
@ -33,6 +33,7 @@ protected:
|
||||
|
||||
bool set_mode(uint8_t mode) override;
|
||||
|
||||
MAV_RESULT _handle_command_preflight_calibration_baro() override;
|
||||
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
||||
|
||||
|
@ -926,7 +926,6 @@ private:
|
||||
void trim_control_surfaces();
|
||||
void trim_radio();
|
||||
bool rc_failsafe_active(void);
|
||||
void init_barometer(bool full_calibration);
|
||||
void init_rangefinder(void);
|
||||
void read_rangefinder(void);
|
||||
void read_airspeed(void);
|
||||
|
@ -1,17 +1,6 @@
|
||||
#include "Plane.h"
|
||||
#include <AP_RSSI/AP_RSSI.h>
|
||||
|
||||
void Plane::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 Plane::init_rangefinder(void)
|
||||
{
|
||||
rangefinder.init();
|
||||
|
@ -587,7 +587,7 @@ void Plane::startup_INS_ground(void)
|
||||
|
||||
// read Baro pressure at ground
|
||||
//-----------------------------
|
||||
init_barometer(true);
|
||||
barometer.calibrate();
|
||||
|
||||
if (airspeed.enabled()) {
|
||||
// initialize airspeed sensor
|
||||
|
Loading…
Reference in New Issue
Block a user