Commit e4f8eea2 authored by Lorenz Meier's avatar Lorenz Meier

QGC: Fix excessive noise terms

parent 9ebd2baf
...@@ -1765,7 +1765,7 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj ...@@ -1765,7 +1765,7 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj
simulation = new QGCFlightGearLink(_vehicle, options); simulation = new QGCFlightGearLink(_vehicle, options);
} }
float noise_scaler = 0.002f; float noise_scaler = 0.0001f;
xacc_var = noise_scaler * 0.2914f; xacc_var = noise_scaler * 0.2914f;
yacc_var = noise_scaler * 0.2914f; yacc_var = noise_scaler * 0.2914f;
zacc_var = noise_scaler * 0.9577f; zacc_var = noise_scaler * 0.9577f;
...@@ -1775,10 +1775,10 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj ...@@ -1775,10 +1775,10 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj
xmag_var = noise_scaler * 0.0786f; xmag_var = noise_scaler * 0.0786f;
ymag_var = noise_scaler * 0.0566f; ymag_var = noise_scaler * 0.0566f;
zmag_var = noise_scaler * 0.0333f; zmag_var = noise_scaler * 0.0333f;
abs_pressure_var = noise_scaler * 1.1604f; abs_pressure_var = noise_scaler * 0.5604f;
diff_pressure_var = noise_scaler * 0.3604f; diff_pressure_var = noise_scaler * 0.2604f;
pressure_alt_var = noise_scaler * 1.1604f; pressure_alt_var = noise_scaler * 0.5604f;
temperature_var = noise_scaler * 2.4290f; temperature_var = noise_scaler * 0.7290f;
// Connect Flight Gear Link // Connect Flight Gear Link
link = dynamic_cast<QGCFlightGearLink*>(simulation); link = dynamic_cast<QGCFlightGearLink*>(simulation);
...@@ -1840,7 +1840,7 @@ void UAS::enableHilXPlane(bool enable) ...@@ -1840,7 +1840,7 @@ void UAS::enableHilXPlane(bool enable)
} }
simulation = new QGCXPlaneLink(_vehicle); simulation = new QGCXPlaneLink(_vehicle);
float noise_scaler = 0.0002f; float noise_scaler = 0.0001f;
xacc_var = noise_scaler * 0.2914f; xacc_var = noise_scaler * 0.2914f;
yacc_var = noise_scaler * 0.2914f; yacc_var = noise_scaler * 0.2914f;
zacc_var = noise_scaler * 0.9577f; zacc_var = noise_scaler * 0.9577f;
...@@ -1850,10 +1850,10 @@ void UAS::enableHilXPlane(bool enable) ...@@ -1850,10 +1850,10 @@ void UAS::enableHilXPlane(bool enable)
xmag_var = noise_scaler * 0.0786f; xmag_var = noise_scaler * 0.0786f;
ymag_var = noise_scaler * 0.0566f; ymag_var = noise_scaler * 0.0566f;
zmag_var = noise_scaler * 0.0333f; zmag_var = noise_scaler * 0.0333f;
abs_pressure_var = noise_scaler * 1.1604f; abs_pressure_var = noise_scaler * 0.5604f;
diff_pressure_var = noise_scaler * 0.3604f; diff_pressure_var = noise_scaler * 0.2604f;
pressure_alt_var = noise_scaler * 1.1604f; pressure_alt_var = noise_scaler * 0.5604f;
temperature_var = noise_scaler * 2.4290f; temperature_var = noise_scaler * 0.7290f;
} }
// Connect X-Plane Link // Connect X-Plane Link
if (enable) if (enable)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment