mirror of https://github.com/ArduPilot/ardupilot
AP_AirSpeed: take EAS2TAS directory from baro; use for all backends
Plane was only setting EAS2TAS in the primary frontend; calibration expected it to be set on each instance.
This commit is contained in:
parent
470e88f8b3
commit
5cfba85095
|
@ -219,9 +219,6 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
|
|||
|
||||
AP_Airspeed::AP_Airspeed()
|
||||
{
|
||||
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
||||
state[i].EAS2TAS = 1;
|
||||
}
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
if (_singleton != nullptr) {
|
||||
|
|
|
@ -101,18 +101,6 @@ public:
|
|||
}
|
||||
float get_differential_pressure(void) const { return get_differential_pressure(primary); }
|
||||
|
||||
// set the apparent to true airspeed ratio
|
||||
void set_EAS2TAS(uint8_t i, float v) {
|
||||
state[i].EAS2TAS = v;
|
||||
}
|
||||
void set_EAS2TAS(float v) { set_EAS2TAS(primary, v); }
|
||||
|
||||
// get the apparent to true airspeed ratio
|
||||
float get_EAS2TAS(uint8_t i) const {
|
||||
return state[i].EAS2TAS;
|
||||
}
|
||||
float get_EAS2TAS(void) const { return get_EAS2TAS(primary); }
|
||||
|
||||
// update airspeed ratio calibration
|
||||
void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal);
|
||||
|
||||
|
@ -186,7 +174,6 @@ private:
|
|||
float last_pressure;
|
||||
float filtered_pressure;
|
||||
float corrected_pressure;
|
||||
float EAS2TAS;
|
||||
bool healthy:1;
|
||||
bool hil_set:1;
|
||||
float hil_pressure;
|
||||
|
|
|
@ -127,7 +127,7 @@ void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t
|
|||
|
||||
// calculate true airspeed, assuming a airspeed ratio of 1.0
|
||||
float dpress = MAX(get_differential_pressure(), 0);
|
||||
float true_airspeed = sqrtf(dpress) * state[i].EAS2TAS;
|
||||
float true_airspeed = sqrtf(dpress) * AP::baro().get_EAS2TAS();
|
||||
|
||||
float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
|
||||
|
||||
|
@ -178,7 +178,7 @@ void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground)
|
|||
vground.y,
|
||||
vground.z,
|
||||
get_differential_pressure(primary),
|
||||
state[primary].EAS2TAS,
|
||||
AP::baro().get_EAS2TAS(),
|
||||
param[primary].ratio.get(),
|
||||
state[primary].calibration.state.x,
|
||||
state[primary].calibration.state.y,
|
||||
|
|
Loading…
Reference in New Issue