Browse Source

Plane: tidy handling of barometer calibrations

mission-4.1.18
Peter Barker 7 years ago committed by Francisco Ferreira
parent
commit
65893cfca5
  1. 17
      ArduPlane/GCS_Mavlink.cpp
  2. 1
      ArduPlane/GCS_Mavlink.h
  3. 1
      ArduPlane/Plane.h
  4. 11
      ArduPlane/sensors.cpp
  5. 2
      ArduPlane/system.cpp

17
ArduPlane/GCS_Mavlink.cpp

@ -849,19 +849,22 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink @@ -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

1
ArduPlane/GCS_Mavlink.h

@ -33,6 +33,7 @@ protected: @@ -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;

1
ArduPlane/Plane.h

@ -926,7 +926,6 @@ private: @@ -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);

11
ArduPlane/sensors.cpp

@ -1,17 +1,6 @@ @@ -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();

2
ArduPlane/system.cpp

@ -587,7 +587,7 @@ void Plane::startup_INS_ground(void) @@ -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…
Cancel
Save