2017-04-12 08:17:19 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_Baro_Backend.h"
|
|
|
|
|
2021-10-29 22:15:47 -03:00
|
|
|
#if AP_SIM_BARO_ENABLED
|
|
|
|
|
2017-04-12 08:17:19 -03:00
|
|
|
#include <AP_Math/vectorN.h>
|
|
|
|
|
2021-10-29 22:15:47 -03:00
|
|
|
#include <SITL/SITL.h>
|
|
|
|
|
2017-04-12 08:17:19 -03:00
|
|
|
class AP_Baro_SITL : public AP_Baro_Backend {
|
|
|
|
public:
|
|
|
|
AP_Baro_SITL(AP_Baro &);
|
|
|
|
|
|
|
|
void update() override;
|
|
|
|
|
2023-01-03 21:44:30 -04:00
|
|
|
// adjust for simulated board temperature
|
|
|
|
static void temperature_adjustment(float &p, float &T);
|
|
|
|
|
|
|
|
// adjust for wind effects
|
|
|
|
static float wind_pressure_correction(uint8_t instance);
|
|
|
|
|
2017-07-12 02:03:33 -03:00
|
|
|
protected:
|
|
|
|
|
2020-06-30 04:03:24 -03:00
|
|
|
void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = healthy(instance); };
|
2017-07-12 02:03:33 -03:00
|
|
|
|
2017-04-12 08:17:19 -03:00
|
|
|
private:
|
2017-07-24 05:57:05 -03:00
|
|
|
uint8_t _instance;
|
2021-07-30 07:12:00 -03:00
|
|
|
SITL::SIM *_sitl;
|
2017-04-12 08:17:19 -03:00
|
|
|
|
|
|
|
// barometer delay buffer variables
|
|
|
|
struct readings_baro {
|
|
|
|
uint32_t time;
|
|
|
|
float data;
|
|
|
|
};
|
2017-07-24 08:00:36 -03:00
|
|
|
uint8_t _store_index;
|
|
|
|
uint32_t _last_store_time;
|
|
|
|
static const uint8_t _buffer_length = 50;
|
|
|
|
VectorN<readings_baro, _buffer_length> _buffer;
|
2017-04-12 08:17:19 -03:00
|
|
|
|
2020-06-30 04:03:24 -03:00
|
|
|
// is the barometer usable for flight
|
|
|
|
bool healthy(uint8_t instance);
|
|
|
|
|
2017-06-21 11:58:39 -03:00
|
|
|
void _timer();
|
|
|
|
bool _has_sample;
|
|
|
|
uint32_t _last_sample_time;
|
|
|
|
float _recent_temp;
|
|
|
|
float _recent_press;
|
2020-08-21 16:15:40 -03:00
|
|
|
float _last_altitude;
|
2017-06-21 11:58:39 -03:00
|
|
|
|
2017-04-12 08:17:19 -03:00
|
|
|
};
|
2021-10-29 22:15:47 -03:00
|
|
|
#endif // AP_SIM_BARO_ENABLED
|