SITL: add baro wind coefficients for Z-axis.

This commit is contained in:
Andy Piper 2022-11-22 20:59:05 +00:00 committed by Andrew Tridgell
parent 5727cfacb9
commit 71a27027f1
2 changed files with 4 additions and 0 deletions

View File

@ -319,6 +319,8 @@ const AP_Param::GroupInfo SIM::BaroParm::var_info[] = {
AP_GROUPINFO("WCF_BAK", 8, SIM::BaroParm, wcof_xn, 0.0),
AP_GROUPINFO("WCF_RGT", 9, SIM::BaroParm, wcof_yp, 0.0),
AP_GROUPINFO("WCF_LFT", 10, SIM::BaroParm, wcof_yn, 0.0),
AP_GROUPINFO("WCF_UP", 11, SIM::BaroParm, wcof_zp, 0.0),
AP_GROUPINFO("WCF_DN", 12, SIM::BaroParm, wcof_zn, 0.0),
AP_GROUPEND
};

View File

@ -254,6 +254,8 @@ public:
AP_Float wcof_xn;
AP_Float wcof_yp;
AP_Float wcof_yn;
AP_Float wcof_zp;
AP_Float wcof_zn;
};
BaroParm baro[BARO_MAX_INSTANCES];