Plane: let GCS_MAVLink calibrate airspeed sensor

Also remove useless zero_airspeed function
This commit is contained in:
Peter Barker 2018-03-28 13:29:46 +11:00 committed by Francisco Ferreira
parent d2ab76b2c6
commit 58d41e40d3
5 changed files with 1 additions and 26 deletions

View File

@ -849,20 +849,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink
return ret;
}
MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration_baro()
{
/*
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 ret;
}
MAV_RESULT GCS_MAVLINK_Plane::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
{
if (is_equal(packet.param4,1.0f)) {

View File

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

View File

@ -929,7 +929,6 @@ private:
void init_rangefinder(void);
void read_rangefinder(void);
void read_airspeed(void);
void zero_airspeed(bool in_startup);
void read_receiver_rssi(void);
void rpm_update(void);
void button_update(void);

View File

@ -96,15 +96,6 @@ void Plane::read_airspeed(void)
}
}
void Plane::zero_airspeed(bool in_startup)
{
airspeed.calibrate(in_startup);
read_airspeed();
// update barometric calibration with new airspeed supplied temperature
barometer.update_calibration();
gcs().send_text(MAV_SEVERITY_INFO,"Airspeed calibration started");
}
// read the receiver RSSI as an 8 bit number for MAVLink
// RC_CHANNELS_SCALED message
void Plane::read_receiver_rssi(void)

View File

@ -592,7 +592,7 @@ void Plane::startup_INS_ground(void)
if (airspeed.enabled()) {
// initialize airspeed sensor
// --------------------------
zero_airspeed(true);
airspeed.calibrate(true);
} else {
gcs().send_text(MAV_SEVERITY_WARNING,"No airspeed");
}