APM:Libraries
AP_Baro_SITL.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_Baro_Backend.h"
4 
5 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 #include <SITL/SITL.h>
7 #include <AP_Math/vectorN.h>
8 
9 class AP_Baro_SITL : public AP_Baro_Backend {
10 public:
12 
13  void update() override;
14 
15 protected:
16 
17  void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = true; }
18 
19 private:
20  uint8_t _instance;
22 
23  // barometer delay buffer variables
24  struct readings_baro {
25  uint32_t time;
26  float data;
27  };
28  uint8_t _store_index;
29  uint32_t _last_store_time;
30  static const uint8_t _buffer_length = 50;
32 
33  // adjust for simulated board temperature
34  void temperature_adjustment(float &p, float &T);
35 
36  void _timer();
39  float _recent_temp;
41 
42 };
43 #endif // CONFIG_HAL_BOARD
AP_Baro_SITL(AP_Baro &)
void update() override
VectorN< readings_baro, _buffer_length > _buffer
Definition: AP_Baro_SITL.h:31
uint32_t _last_store_time
Definition: AP_Baro_SITL.h:29
struct AP_Baro::sensor sensors[BARO_MAX_INSTANCES]
AP_Baro & _frontend
float _recent_temp
Definition: AP_Baro_SITL.h:39
float _recent_press
Definition: AP_Baro_SITL.h:40
void temperature_adjustment(float &p, float &T)
uint32_t _last_sample_time
Definition: AP_Baro_SITL.h:38
static const uint8_t _buffer_length
Definition: AP_Baro_SITL.h:30
uint8_t _instance
Definition: AP_Baro_SITL.h:20
void update_healthy_flag(uint8_t instance) override
Definition: AP_Baro_SITL.h:17
bool _has_sample
Definition: AP_Baro_SITL.h:37
SITL::SITL * _sitl
Definition: AP_Baro_SITL.h:21
uint8_t _store_index
Definition: AP_Baro_SITL.h:28