mirror of
https://github.com/okalachev/flix.git
synced 2025-07-27 17:49:33 +00:00
Use simulated IMU noise values from MPU9250 datasheet
This commit is contained in:
parent
89bf8a7f14
commit
e360110430
@ -60,52 +60,34 @@
|
|||||||
<angular_velocity>
|
<angular_velocity>
|
||||||
<x>
|
<x>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<stddev>0.00174533</stddev><!-- 0.1 degrees per second -->
|
||||||
<stddev>1.5e-2</stddev>
|
|
||||||
<!-- <bias_mean>0.0000075</bias_mean>
|
|
||||||
<bias_stddev>0.0000008</bias_stddev> -->
|
|
||||||
</noise>
|
</noise>
|
||||||
</x>
|
</x>
|
||||||
<y>
|
<y>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<stddev>0.00174533</stddev>
|
||||||
<stddev>1.5e-2</stddev>
|
|
||||||
<!-- <bias_mean>0.0000075</bias_mean>
|
|
||||||
<bias_stddev>0.0000008</bias_stddev> -->
|
|
||||||
</noise>
|
</noise>
|
||||||
</y>
|
</y>
|
||||||
<z>
|
<z>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<stddev>0.00174533</stddev>
|
||||||
<stddev>1.5e-2</stddev>
|
|
||||||
<!-- <bias_mean>0.0000075</bias_mean>
|
|
||||||
<bias_stddev>0.0000008</bias_stddev> -->
|
|
||||||
</noise>
|
</noise>
|
||||||
</z>
|
</z>
|
||||||
</angular_velocity>
|
</angular_velocity>
|
||||||
<linear_acceleration>
|
<linear_acceleration>
|
||||||
<x>
|
<x>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<stddev>0.0784</stddev><!-- 8 mg -->
|
||||||
<stddev>3.5e-1</stddev>
|
|
||||||
<!-- <bias_mean>0.1</bias_mean>
|
|
||||||
<bias_stddev>0.001</bias_stddev> -->
|
|
||||||
</noise>
|
</noise>
|
||||||
</x>
|
</x>
|
||||||
<y>
|
<y>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<stddev>0.0784</stddev>
|
||||||
<stddev>3.5e-1</stddev>
|
|
||||||
<!-- <bias_mean>0.1</bias_mean>
|
|
||||||
<bias_stddev>0.001</bias_stddev> -->
|
|
||||||
</noise>
|
</noise>
|
||||||
</y>
|
</y>
|
||||||
<z>
|
<z>
|
||||||
<noise type="gaussian">
|
<noise type="gaussian">
|
||||||
<mean>0.0</mean>
|
<stddev>0.0784</stddev>
|
||||||
<stddev>3.5e-1</stddev>
|
|
||||||
<!-- <bias_mean>0.1</bias_mean>
|
|
||||||
<bias_stddev>0.001</bias_stddev> -->
|
|
||||||
</noise>
|
</noise>
|
||||||
</z>
|
</z>
|
||||||
</linear_acceleration>
|
</linear_acceleration>
|
||||||
|
Loading…
x
Reference in New Issue
Block a user