100 lines
2.8 KiB
Plaintext
100 lines
2.8 KiB
Plaintext
|
<?xml version="1.0" ?>
|
||
|
<sdf version="1.5">
|
||
|
<world name="default">
|
||
|
<model name="box_imu_noise">
|
||
|
<pose>2 0 5 0 0 0</pose>
|
||
|
<link name="link">
|
||
|
<inertial>
|
||
|
<inertia>
|
||
|
<ixx>1.8</ixx>
|
||
|
<ixy>0.0</ixy>
|
||
|
<ixz>0.0</ixz>
|
||
|
<iyy>10.8</iyy>
|
||
|
<iyz>0.0</iyz>
|
||
|
<izz>10.8</izz>
|
||
|
</inertia>
|
||
|
<mass>10.0</mass>
|
||
|
</inertial>
|
||
|
<collision name="collision">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>3.6 0.2 0.2</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<visual name="visual">
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>3.6 0.2 0.2</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<ambient>0.2 0.2 0.2 1.0</ambient>
|
||
|
<diffuse>.421 0.225 0.0 1.0</diffuse>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<sensor name='imu_sensor' type='imu'>
|
||
|
<always_on>1</always_on>
|
||
|
<update_rate>1000</update_rate>
|
||
|
<imu>
|
||
|
<angular_velocity>
|
||
|
<x>
|
||
|
<noise type="gaussian">
|
||
|
<mean>0</mean>
|
||
|
<stddev>0.0002</stddev>
|
||
|
<bias_mean>7.5e-06</bias_mean>
|
||
|
<bias_stddev>8e-07</bias_stddev>
|
||
|
</noise>
|
||
|
</x>
|
||
|
<y>
|
||
|
<noise type="gaussian">
|
||
|
<mean>0</mean>
|
||
|
<stddev>0.0002</stddev>
|
||
|
<bias_mean>7.5e-06</bias_mean>
|
||
|
<bias_stddev>8e-07</bias_stddev>
|
||
|
</noise>
|
||
|
</y>
|
||
|
<z>
|
||
|
<noise type="gaussian">
|
||
|
<mean>0</mean>
|
||
|
<stddev>0.0002</stddev>
|
||
|
<bias_mean>7.5e-06</bias_mean>
|
||
|
<bias_stddev>8e-07</bias_stddev>
|
||
|
</noise>
|
||
|
</z>
|
||
|
</angular_velocity>
|
||
|
|
||
|
<linear_acceleration>
|
||
|
<x>
|
||
|
<noise type="gaussian">
|
||
|
<mean>0</mean>
|
||
|
<stddev>0.017</stddev>
|
||
|
<bias_mean>0.1</bias_mean>
|
||
|
<bias_stddev>0.001</bias_stddev>
|
||
|
</noise>
|
||
|
</x>
|
||
|
<y>
|
||
|
<noise type="gaussian">
|
||
|
<mean>0</mean>
|
||
|
<stddev>0.017</stddev>
|
||
|
<bias_mean>0.1</bias_mean>
|
||
|
<bias_stddev>0.001</bias_stddev>
|
||
|
</noise>
|
||
|
</y>
|
||
|
<z>
|
||
|
<noise type="gaussian">
|
||
|
<mean>0</mean>
|
||
|
<stddev>0.017</stddev>
|
||
|
<bias_mean>0.1</bias_mean>
|
||
|
<bias_stddev>0.001</bias_stddev>
|
||
|
</noise>
|
||
|
</z>
|
||
|
</linear_acceleration>
|
||
|
</imu>
|
||
|
</sensor>
|
||
|
</link>
|
||
|
</model>
|
||
|
|
||
|
</world>
|
||
|
</sdf>
|