pxmlw6n2f/Gazebo_Distributed_TCP/worlds/ray_noise_plugin.world

61 lines
1.6 KiB
Plaintext
Raw Permalink Normal View History

2019-03-28 10:57:49 +08:00
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<model name="noisy_ray">
<pose>0 0 0.1 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.2 0.2 0.2</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 0.2 0.2</size>
</box>
</geometry>
</visual>
<sensor name="laser" type="ray">
<pose>0.1 0 0.0175 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-1.26889</min_angle>
<max_angle>1.268899</max_angle>
</horizontal>
</scan>
<range>
<min>0.1</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>custom</type>
</noise>
</ray>
<plugin name="laser" filename="libRaySensorNoisePlugin.so" />
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</world>
</sdf>