mirror of https://github.com/ArduPilot/ardupilot
SITL: added barometer wind coefficients
This commit is contained in:
parent
567de3047b
commit
b7f68e87b4
|
@ -349,6 +349,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
|||
fdm.yawDeg = degrees(y);
|
||||
fdm.quaternion.from_rotation_matrix(dcm);
|
||||
fdm.airspeed = airspeed_pitot;
|
||||
fdm.velocity_air_bf = velocity_air_bf;
|
||||
fdm.battery_voltage = battery_voltage;
|
||||
fdm.battery_current = battery_current;
|
||||
fdm.num_motors = num_motors;
|
||||
|
|
|
@ -269,6 +269,12 @@ const AP_Param::GroupInfo SITL::BaroParm::var_info[] = {
|
|||
AP_GROUPINFO("GLITCH", 4, SITL::BaroParm, glitch, 0),
|
||||
AP_GROUPINFO("FREEZE", 5, SITL::BaroParm, freeze, 0),
|
||||
AP_GROUPINFO("DELAY", 6, SITL::BaroParm, delay, 0),
|
||||
|
||||
// wind coeffients
|
||||
AP_GROUPINFO("WCF_FWD", 7, SITL::BaroParm, wcof_xp, 0.0),
|
||||
AP_GROUPINFO("WCF_BAK", 8, SITL::BaroParm, wcof_xn, 0.0),
|
||||
AP_GROUPINFO("WCF_RGT", 9, SITL::BaroParm, wcof_yp, 0.0),
|
||||
AP_GROUPINFO("WCF_LFT", 10, SITL::BaroParm, wcof_yn, 0.0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -54,6 +54,7 @@ struct sitl_fdm {
|
|||
double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
|
||||
Quaternion quaternion;
|
||||
double airspeed; // m/s
|
||||
Vector3f velocity_air_bf; // velocity relative to airmass, body frame
|
||||
double battery_voltage; // Volts
|
||||
double battery_current; // Amps
|
||||
double battery_remaining; // Ah, if non-zero capacity
|
||||
|
@ -244,6 +245,12 @@ public:
|
|||
AP_Int8 freeze; // freeze baro to last recorded altitude
|
||||
AP_Int8 disable; // disable simulated barometers
|
||||
AP_Int16 delay; // barometer data delay in ms
|
||||
|
||||
// wind coefficients
|
||||
AP_Float wcof_xp;
|
||||
AP_Float wcof_xn;
|
||||
AP_Float wcof_yp;
|
||||
AP_Float wcof_yn;
|
||||
};
|
||||
BaroParm baro[BARO_MAX_INSTANCES];
|
||||
|
||||
|
|
Loading…
Reference in New Issue