APM:Libraries
AP_Baro_Backend.cpp
Go to the documentation of this file.
1 #include "AP_Baro_Backend.h"
2 #include <stdio.h>
3 
4 extern const AP_HAL::HAL& hal;
5 
6 // constructor
8  _frontend(baro)
9 {
10  _sem = hal.util->new_semaphore();
11 }
12 
14 {
15  if (instance >= _frontend._num_sensors) {
16  return;
17  }
18  if (!_sem->take_nonblocking()) {
19  return;
20  }
21 
22  // consider a sensor as healthy if it has had an update in the
23  // last 0.5 seconds and values are non-zero and have changed within the last 2 seconds
24  const uint32_t now = AP_HAL::millis();
25  _frontend.sensors[instance].healthy =
26  (now - _frontend.sensors[instance].last_update_ms < BARO_TIMEOUT_MS) &&
28  !is_zero(_frontend.sensors[instance].pressure);
29 
30  _sem->give();
31 }
32 
33 void AP_Baro_Backend::backend_update(uint8_t instance)
34 {
35  update();
36  update_healthy_flag(instance);
37 }
38 
39 
40 /*
41  copy latest data to the frontend from a backend
42  */
43 void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float temperature)
44 {
45  if (instance >= _frontend._num_sensors) {
46  return;
47  }
48  uint32_t now = AP_HAL::millis();
49 
50  // check for changes in data values
51  if (!is_equal(_frontend.sensors[instance].pressure, pressure) || !is_equal(_frontend.sensors[instance].temperature, temperature)) {
52  _frontend.sensors[instance].last_change_ms = now;
53  }
54 
55  // update readings
56  _frontend.sensors[instance].pressure = pressure;
58  _frontend.sensors[instance].last_update_ms = now;
59 }
60 
61 static constexpr float FILTER_KOEF = 0.1f;
62 
63 /* Check that the baro value is valid by using a mean filter. If the
64  * value is further than filtrer_range from mean value, it is
65  * rejected.
66 */
68 {
69 
70  if (isinf(press) || isnan(press)) {
71  return false;
72  }
73 
74  const float range = (float)_frontend.get_filter_range();
75  if (range <= 0) {
76  return true;
77  }
78 
79  bool ret = true;
80  if (is_zero(_mean_pressure)) {
81  _mean_pressure = press;
82  } else {
83  const float d = fabsf(_mean_pressure - press) / (_mean_pressure + press); // diff divide by mean value in percent ( with the * 200.0f on later line)
84  float koeff = FILTER_KOEF;
85 
86  if (d * 200.0f > range) { // check the difference from mean value outside allowed range
87  // printf("\nBaro pressure error: mean %f got %f\n", (double)_mean_pressure, (double)press );
88  ret = false;
89  koeff /= (d * 10.0f); // 2.5 and more, so one bad sample never change mean more than 4%
90  _error_count++;
91  }
92  _mean_pressure = _mean_pressure * (1 - koeff) + press * koeff; // complimentary filter 1/k
93  }
94  return ret;
95 }
uint32_t _error_count
virtual void update_healthy_flag(uint8_t instance)
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
AP_HAL::Semaphore * _sem
uint8_t get_filter_range() const
Definition: AP_Baro.h:178
#define BARO_DATA_CHANGE_TIMEOUT_MS
Definition: AP_Baro.h:17
AP_HAL::Util * util
Definition: HAL.h:115
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
struct AP_Baro::sensor sensors[BARO_MAX_INSTANCES]
#define BARO_TIMEOUT_MS
Definition: AP_Baro.h:16
float temperature
Definition: Airspeed.cpp:32
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Baro & _frontend
#define constexpr
Definition: AP_HAL_Macros.h:16
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
uint32_t last_change_ms
Definition: AP_Baro.h:203
static AP_Baro baro
Definition: ModuleTest.cpp:18
uint32_t millis()
Definition: system.cpp:157
bool pressure_ok(float press)
virtual bool give()=0
static constexpr float FILTER_KOEF
uint32_t last_update_ms
Definition: AP_Baro.h:202
void backend_update(uint8_t instance)
AP_Baro_Backend(AP_Baro &baro)
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
float temperature
Definition: AP_Baro.h:208
uint8_t _num_sensors
Definition: AP_Baro.h:193
float pressure
Definition: AP_Baro.h:207
virtual void update()=0