AP_Airspeed: added EAS2TAS in airspeed driver
this keeps the true airspeed ratio in the airspeed driver, which seems the most logical place
This commit is contained in:
parent
9bbe6c1967
commit
3c66cb8af1
@ -26,7 +26,6 @@ private:
|
||||
const float Q1; // process noise matrix bottom right element
|
||||
Vector3f state; // state vector
|
||||
const float DT; // time delta
|
||||
|
||||
};
|
||||
|
||||
class AP_Airspeed
|
||||
@ -34,7 +33,8 @@ class AP_Airspeed
|
||||
public:
|
||||
// constructor
|
||||
AP_Airspeed() :
|
||||
_ets_fd(-1)
|
||||
_ets_fd(-1),
|
||||
_EAS2TAS(1.0f)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
};
|
||||
@ -99,8 +99,18 @@ public:
|
||||
return max(_last_pressure - _offset, 0);
|
||||
}
|
||||
|
||||
// set the apparent to true airspeed ratio
|
||||
void set_EAS2TAS(float v) {
|
||||
_EAS2TAS = v;
|
||||
}
|
||||
|
||||
// get the apparent to true airspeed ratio
|
||||
float get_EAS2TAS(void) const {
|
||||
return _EAS2TAS;
|
||||
}
|
||||
|
||||
// update airspeed ratio calibration
|
||||
void update_calibration(Vector3f vground, float EAS2TAS);
|
||||
void update_calibration(Vector3f vground);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -116,6 +126,7 @@ private:
|
||||
float _airspeed;
|
||||
int _ets_fd;
|
||||
float _last_pressure;
|
||||
float _EAS2TAS;
|
||||
|
||||
Airspeed_Calibration _calibration;
|
||||
float _last_saved_ratio;
|
||||
|
@ -2,7 +2,7 @@
|
||||
/*
|
||||
* auto_calibration.cpp - airspeed auto calibration
|
||||
|
||||
* Algorithm by Paul Riseborough
|
||||
* Algorithm by Paul Riseborough
|
||||
*
|
||||
*/
|
||||
|
||||
@ -102,15 +102,15 @@ float Airspeed_Calibration::update(float airspeed, const Vector3f &vg)
|
||||
/*
|
||||
called once a second to do calibration update
|
||||
*/
|
||||
void AP_Airspeed::update_calibration(Vector3f vground, float EAS2TAS)
|
||||
void AP_Airspeed::update_calibration(Vector3f vground)
|
||||
{
|
||||
if (!_autocal) {
|
||||
// auto-calibration not enabled
|
||||
return;
|
||||
}
|
||||
// calculate true airspeed, assuming a ratio of 1.0
|
||||
float airspeed = sqrtf(get_differential_pressure()) * EAS2TAS;
|
||||
float ratio = _calibration.update(airspeed, vground);
|
||||
// calculate true airspeed, assuming a airspeed ratio of 1.0
|
||||
float true_airspeed = sqrtf(get_differential_pressure()) * _EAS2TAS;
|
||||
float ratio = _calibration.update(true_airspeed, vground);
|
||||
if (isnan(ratio) || isinf(ratio)) {
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user