Skip to content

Commit

Permalink
AP_Airspeed: Correct airspeed calibration issue for gliders with sens…
Browse files Browse the repository at this point in the history
…ors positioned behind the propeller
  • Loading branch information
mduclehcm committed Feb 4, 2025
1 parent eed3e14 commit dbdef16
Showing 1 changed file with 8 additions and 0 deletions.
8 changes: 8 additions & 0 deletions libraries/AP_Airspeed/Airspeed_Calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h>
#include <SRV_Channel/SRV_Channel.h>

#include "AP_Airspeed.h"

Expand Down Expand Up @@ -122,6 +123,13 @@ void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t
return;
}

if (param[i].use == 2 && !is_zero(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))) {
// special case for gliders with airspeed sensors behind the
// propeller. Allow airspeed to be disabled when throttle is
// running
return;
}

// set state.z based on current ratio, this allows the operator to
// override the current ratio in flight with autocal, which is
// very useful both for testing and to force a reasonable value.
Expand Down

0 comments on commit dbdef16

Please sign in to comment.