mirror of
https://gitlab.com/yikestone/qt_pi.git
synced 2025-08-03 13:44:12 +05:30
63 lines
1.5 KiB
XML
63 lines
1.5 KiB
XML
<?xml version="1.0" ?>
|
|
<sdf version="1.3">
|
|
<model name="hokuyo">
|
|
<pose>0 0 0.035 0 0 0</pose>
|
|
<link name="link">
|
|
<inertial>
|
|
<mass>0.1</mass>
|
|
</inertial>
|
|
<visual name="visual">
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
|
|
<collision name="collision-base">
|
|
<pose>0 0 -0.0145 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.05 0.05 0.041</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
|
|
<collision name="collision-top">
|
|
<pose>0 0 0.0205 0 0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.021</radius>
|
|
<length>0.029</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
|
|
|
|
<sensor name="laser" type="ray">
|
|
<pose>0.01 0 0.0175 0 -0 0</pose>
|
|
<ray>
|
|
<scan>
|
|
<horizontal>
|
|
<samples>640</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>-2.26889</min_angle>
|
|
<max_angle>2.268899</max_angle>
|
|
</horizontal>
|
|
</scan>
|
|
<range>
|
|
<min>0.08</min>
|
|
<max>10</max>
|
|
<resolution>0.01</resolution>
|
|
</range>
|
|
</ray>
|
|
|
|
<plugin name="laser" filename="libRayPlugin.so" />
|
|
<always_on>1</always_on>
|
|
<update_rate>30</update_rate>
|
|
<visualize>true</visualize>
|
|
</sensor>
|
|
</link>
|
|
</model>
|
|
</sdf>
|