Skip to content

Commit

Permalink
add imu sensor model noise
Browse files Browse the repository at this point in the history
Signed-off-by: frede791 <[email protected]>
  • Loading branch information
frede791 authored and dagar committed Feb 22, 2024
1 parent 2228336 commit 953e02b
Show file tree
Hide file tree
Showing 7 changed files with 378 additions and 1 deletion.
54 changes: 54 additions & 0 deletions models/advanced_plane/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,60 @@
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
Expand Down
54 changes: 54 additions & 0 deletions models/omnicopter/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,60 @@
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00018665</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00018665</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00018665</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00186</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00186</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00186</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
<sensor name="navsat_sensor" type="navsat">
<always_on>1</always_on>
Expand Down
55 changes: 54 additions & 1 deletion models/px4vision/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -73,9 +73,62 @@
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00018665</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00018665</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00018665</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00186</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00186</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.00186</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
</link>
<!-- TODO: add IMU plugin -->
<link name='rotor_0'>
<pose>0.0935 -0.107 0.03 0 0 0</pose>
<inertial>
Expand Down
54 changes: 54 additions & 0 deletions models/r1_rover/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,60 @@
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
Expand Down
54 changes: 54 additions & 0 deletions models/rc_cessna/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,60 @@
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
<sensor name="navsat_sensor" type="navsat">
<always_on>1</always_on>
Expand Down
54 changes: 54 additions & 0 deletions models/standard_vtol/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,60 @@
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0003394</stddev>
<dynamic_bias_stddev>3.8785e-05</dynamic_bias_stddev>
<dynamic_bias_correlation_time>1000</dynamic_bias_correlation_time>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.004</stddev>
<dynamic_bias_stddev>0.006</dynamic_bias_stddev>
<dynamic_bias_correlation_time>300</dynamic_bias_correlation_time>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
Expand Down
Loading

0 comments on commit 953e02b

Please sign in to comment.