|
|
|
@ -2930,6 +2930,21 @@ void UAS::enableHilXPlane(bool enable)
@@ -2930,6 +2930,21 @@ void UAS::enableHilXPlane(bool enable)
|
|
|
|
|
} |
|
|
|
|
qDebug() << "CREATED NEW XPLANE LINK"; |
|
|
|
|
simulation = new QGCXPlaneLink(this); |
|
|
|
|
|
|
|
|
|
float noise_scaler = 0.1f; |
|
|
|
|
xacc_var = noise_scaler * 1.2914f; |
|
|
|
|
yacc_var = noise_scaler * 0.7048f; |
|
|
|
|
zacc_var = noise_scaler * 1.9577f; |
|
|
|
|
rollspeed_var = noise_scaler * 0.8126f; |
|
|
|
|
pitchspeed_var = noise_scaler * 0.6145f; |
|
|
|
|
yawspeed_var = noise_scaler * 0.5852f; |
|
|
|
|
xmag_var = noise_scaler * 0.4786f; |
|
|
|
|
ymag_var = noise_scaler * 0.4566f; |
|
|
|
|
zmag_var = noise_scaler * 0.3333f; |
|
|
|
|
abs_pressure_var = noise_scaler * 1.1604f; |
|
|
|
|
diff_pressure_var = noise_scaler * 0.6604f; |
|
|
|
|
pressure_alt_var = noise_scaler * 1.1604f; |
|
|
|
|
temperature_var = noise_scaler * 2.4290f; |
|
|
|
|
} |
|
|
|
|
// Connect X-Plane Link
|
|
|
|
|
if (enable) |
|
|
|
|