Airspeed Selector: repurpose wind estimator into an airspeed (selection, validation) module.

This new airspeed module does:
  -runns an airspeed validator for every airspeed sensor present, which checks measurement validity and estimates an airspeed scale
  -selects another airspeed sensor if for the current one a failure is detected
  -estimates airspeed with groundspeed-windspeed if no valid airspeed sensor is present
  -outputs airspeed_validated topic

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer
2019-08-07 13:06:00 +02:00
committed by Roman Bapst
parent 970e362e9a
commit cedf14e2ba
65 changed files with 767 additions and 461 deletions
+10
View File
@@ -0,0 +1,10 @@
uint64 timestamp # time since system start (microseconds)
float32 indicated_airspeed_m_s # indicated airspeed in m/s (IAS), set to NAN if invalid
float32 equivalent_airspeed_m_s # equivalent airspeed in m/s (accounts for instrumentation errors) (EAS), set to NAN if invalid
float32 true_airspeed_m_s # true filtered airspeed in m/s (TAS), set to NAN if invalid
float32 true_ground_minus_wind_m_s # TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid
float32 indicated_ground_minus_wind_m_s # IAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid
int8 selected_airspeed_index # 0-2: airspeed sensor index, -1: groundspeed-windspeed, -2: airspeed invalid