mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SITL: add baro wind coefficients for Z-axis.
This commit is contained in:
parent
5727cfacb9
commit
71a27027f1
@ -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
|
||||
};
|
||||
|
||||
|
@ -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];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user