Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Baro/AP_Baro_SITL.cpp
Views: 1798
#include "AP_Baro_SITL.h"12#if AP_SIM_BARO_ENABLED34#include <AP_HAL/AP_HAL.h>5#include <AP_Vehicle/AP_Vehicle_Type.h>67extern const AP_HAL::HAL& hal;89/*10constructor - registers instance at top Baro driver11*/12AP_Baro_SITL::AP_Baro_SITL(AP_Baro &baro) :13AP_Baro_Backend(baro),14_sitl(AP::sitl()),15_has_sample(false)16{17if (_sitl != nullptr) {18_instance = _frontend.register_sensor();19#if APM_BUILD_TYPE(APM_BUILD_ArduSub)20_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);21#endif22set_bus_id(_instance, AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, 0, _instance, DEVTYPE_BARO_SITL));23hal.scheduler->register_timer_process(FUNCTOR_BIND(this, &AP_Baro_SITL::_timer, void));24}25}2627// adjust for board temperature warmup on start-up28void AP_Baro_SITL::temperature_adjustment(float &p, float &T)29{30const float tsec = AP_HAL::millis() * 0.001f;31const float T_sensor = T + AP::sitl()->temp_board_offset;32const float tconst = AP::sitl()->temp_tconst;33if (tsec < 23 * tconst) { // time which past the equation below equals T_sensor within approx. 1E-934const float T0 = AP::sitl()->temp_start;35T = T_sensor - (T_sensor - T0) * expf(-tsec / tconst);36}37else {38T = T_sensor;39}4041const float baro_factor = AP::sitl()->temp_baro_factor;42const float Tzero = 30.0f; // start baro adjustment at 30C43if (is_positive(baro_factor)) {44// this produces a pressure change with temperature that45// closely matches what has been observed with a ICM-2078946// barometer. A typical factor is 1.2.47p -= powf(MAX(T - Tzero, 0), baro_factor);48}49}5051void AP_Baro_SITL::_timer()52{5354// 100Hz55const uint32_t now = AP_HAL::millis();56if ((now - _last_sample_time) < 10) {57return;58}59_last_sample_time = now;6061float sim_alt = _sitl->state.altitude;6263if (_sitl->baro[_instance].disable) {64// barometer is disabled65return;66}6768const auto drift_delta_t_ms = now - last_drift_delta_t_ms;69last_drift_delta_t_ms = now;70total_alt_drift += _sitl->baro[_instance].drift * drift_delta_t_ms * 0.001f;7172sim_alt += total_alt_drift;73sim_alt += _sitl->baro[_instance].noise * rand_float();7475// add baro glitch76sim_alt += _sitl->baro[_instance].glitch;7778// add delay79uint32_t best_time_delta = 200; // initialise large time representing buffer entry closest to current time - delay.80uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.8182// storing data from sensor to buffer83if (now - _last_store_time >= 10) { // store data every 10 ms.84_last_store_time = now;85if (_store_index > _buffer_length - 1) { // reset buffer index if index greater than size of buffer86_store_index = 0;87}8889// if freezed barometer, report altitude to last recorded altitude90if (_sitl->baro[_instance].freeze == 1) {91sim_alt = _last_altitude;92} else {93_last_altitude = sim_alt;94}9596_buffer[_store_index].data = sim_alt; // add data to current index97_buffer[_store_index].time = _last_store_time; // add time_stamp to current index98_store_index = _store_index + 1; // increment index99}100101// return delayed measurement102const uint32_t delayed_time = now - _sitl->baro[_instance].delay; // get time corresponding to delay103104// find data corresponding to delayed time in buffer105for (uint8_t i = 0; i <= _buffer_length - 1; i++) {106// find difference between delayed time and time stamp in buffer107uint32_t time_delta = abs(108(int32_t)(delayed_time - _buffer[i].time));109// if this difference is smaller than last delta, store this time110if (time_delta < best_time_delta) {111best_index = i;112best_time_delta = time_delta;113}114}115if (best_time_delta < 200) { // only output stored state if < 200 msec retrieval error116sim_alt = _buffer[best_index].data;117}118119#if !APM_BUILD_TYPE(APM_BUILD_ArduSub)120float p, T_K;121AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, T_K);122float T = KELVIN_TO_C(T_K);123temperature_adjustment(p, T);124#else125float rho, delta, theta;126AP_Baro::SimpleUnderWaterAtmosphere(-sim_alt * 0.001f, rho, delta, theta);127float p = SSL_AIR_PRESSURE * delta;128float T = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta);129#endif130131// add in correction for wind effects132p += wind_pressure_correction(_instance);133134_recent_press = p;135_recent_temp = T;136_has_sample = true;137}138139// unhealthy if baro is turned off or beyond supported instances140bool AP_Baro_SITL::healthy(uint8_t instance)141{142return _last_sample_time != 0 && !_sitl->baro[instance].disable;143}144145// Read the sensor146void AP_Baro_SITL::update(void)147{148if (!_has_sample) {149return;150}151152WITH_SEMAPHORE(_sem);153_copy_to_frontend(_instance, _recent_press, _recent_temp);154_has_sample = false;155}156157/*158return pressure correction for wind based on SIM_BARO_WCF parameters159*/160float AP_Baro_SITL::wind_pressure_correction(uint8_t instance)161{162const auto &bp = AP::sitl()->baro[instance];163164// correct for static pressure position errors165const Vector3f &airspeed_vec_bf = AP::sitl()->state.velocity_air_bf;166167float error = 0.0;168const float sqx = sq(airspeed_vec_bf.x);169const float sqy = sq(airspeed_vec_bf.y);170const float sqz = sq(airspeed_vec_bf.z);171172if (is_positive(airspeed_vec_bf.x)) {173error += bp.wcof_xp * sqx;174} else {175error += bp.wcof_xn * sqx;176}177if (is_positive(airspeed_vec_bf.y)) {178error += bp.wcof_yp * sqy;179} else {180error += bp.wcof_yn * sqy;181}182if (is_positive(airspeed_vec_bf.z)) {183error += bp.wcof_zp * sqz;184} else {185error += bp.wcof_zn * sqz;186}187188return error * 0.5 * SSL_AIR_DENSITY * AP::baro()._get_air_density_ratio();189}190191#endif // AP_SIM_BARO_ENABLED192193194