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_Wind.cpp
Views: 1798
#include "AP_Baro.h"1#include <AP_AHRS/AP_AHRS.h>23#if HAL_BARO_WIND_COMP_ENABLED45// table of compensation coefficient parameters for one baro6const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = {78// @Param: ENABLE9// @DisplayName: Wind coefficient enable10// @Description: This enables the use of wind coefficients for barometer compensation11// @Values: 0:Disabled, 1:Enabled12// @User: Advanced13AP_GROUPINFO_FLAGS("ENABLE", 1, WindCoeff, enable, 0, AP_PARAM_FLAG_ENABLE),1415// @Param: FWD16// @DisplayName: Pressure error coefficient in positive X direction (forward)17// @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.18// @Range: -1.0 1.019// @Increment: 0.0520// @User: Advanced21AP_GROUPINFO("FWD", 2, WindCoeff, xp, 0.0),2223// @Param: BCK24// @DisplayName: Pressure error coefficient in negative X direction (backwards)25// @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.26// @Range: -1.0 1.027// @Increment: 0.0528// @User: Advanced29AP_GROUPINFO("BCK", 3, WindCoeff, xn, 0.0),3031// @Param: RGT32// @DisplayName: Pressure error coefficient in positive Y direction (right)33// @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.34// @Range: -1.0 1.035// @Increment: 0.0536// @User: Advanced37AP_GROUPINFO("RGT", 4, WindCoeff, yp, 0.0),3839// @Param: LFT40// @DisplayName: Pressure error coefficient in negative Y direction (left)41// @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.42// @Range: -1.0 1.043// @Increment: 0.0544// @User: Advanced45AP_GROUPINFO("LFT", 5, WindCoeff, yn, 0.0),4647// @Param: UP48// @DisplayName: Pressure error coefficient in positive Z direction (up)49// @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during climbing flight (or forward flight with a high forwards lean angle), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.50// @Range: -1.0 1.051// @Increment: 0.0552// @User: Advanced53AP_GROUPINFO("UP", 6, WindCoeff, zp, 0.0),5455// @Param: DN56// @DisplayName: Pressure error coefficient in negative Z direction (down)57// @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during descending flight (or forward flight with a high backwards lean angle, eg braking manoeuvre), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.58// @Range: -1.0 1.059// @Increment: 0.0560// @User: Advanced61AP_GROUPINFO("DN", 7, WindCoeff, zn, 0.0),6263AP_GROUPEND64};656667/*68return pressure correction for wind based on GND_WCOEF parameters69*/70float AP_Baro::wind_pressure_correction(uint8_t instance)71{72const WindCoeff &wcoef = sensors[instance].wind_coeff;7374if (!wcoef.enable) {75return 0;76}7778auto &ahrs = AP::ahrs();7980// correct for static pressure position errors81Vector3f airspeed_vec_bf;82if (!ahrs.airspeed_vector_true(airspeed_vec_bf)) {83return 0;84}8586float error = 0.0;8788const float kp = 0.5 * SSL_AIR_DENSITY * ahrs.get_air_density_ratio();89const float sqxp = sq(airspeed_vec_bf.x) * kp;90const float sqyp = sq(airspeed_vec_bf.y) * kp;91const float sqzp = sq(airspeed_vec_bf.z) * kp;9293if (is_positive(airspeed_vec_bf.x)) {94sensors[instance].dynamic_pressure.x = sqxp;95error += wcoef.xp * sqxp;96} else {97sensors[instance].dynamic_pressure.x = -sqxp;98error += wcoef.xn * sqxp;99}100if (is_positive(airspeed_vec_bf.y)) {101sensors[instance].dynamic_pressure.y = sqyp;102error += wcoef.yp * sqyp;103} else {104sensors[instance].dynamic_pressure.y = -sqyp;105error += wcoef.yn * sqyp;106}107if (is_positive(airspeed_vec_bf.z)) {108sensors[instance].dynamic_pressure.z = sqzp;109error += wcoef.zp * sqzp;110} else {111sensors[instance].dynamic_pressure.z = -sqzp;112error += wcoef.zn * sqzp;113}114115return error;116}117#endif // HAL_BARO_WIND_COMP_ENABLED118119120