#include "SIM_MS5525.h" #include using namespace SITL; void MS5525::convert_forward(int32_t D1, int32_t D2, float &P_Pa, float &Temp_C) { const uint8_t Q1 = Qx_coeff[0]; const uint8_t Q2 = Qx_coeff[1]; const uint8_t Q3 = Qx_coeff[2]; const uint8_t Q4 = Qx_coeff[3]; const uint8_t Q5 = Qx_coeff[4]; const uint8_t Q6 = Qx_coeff[5]; // this is the forward conversion copied from the driver: float dT = float(D2) - int64_t(prom[5]) * (1L< p_error_max) { AP_HAL::panic("Invalid pressure conversion: error %f Pa > %f Pa error max", p_error, p_error_max); } const float t_error = fabs(f_Temp_C - Temp_C); const float t_error_max = 0.01; if (t_error > t_error_max) { AP_HAL::panic("Invalid temperature conversion: error %f degC > %f degC error max", t_error, t_error_max); } } void MS5525::get_pressure_temperature_readings(float &P_Pa, float &Temp_C) { float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); Temp_C = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt); const uint8_t instance = 0; // TODO: work out which sensor this is P_Pa = AP::sitl()->state.airspeed_raw_pressure[instance] + AP::sitl()->airspeed[instance].offset; }