fixed a problem of 2-D LiDar
This commit is contained in:
parent
d073317603
commit
ce24723610
|
@ -3,30 +3,32 @@
|
|||
<model name="hokuyo_lidar">
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<link name="link">
|
||||
<inertial>
|
||||
<mass>0.001</mass>
|
||||
<inertia> <!-- inertias are tricky to compute -->
|
||||
<ixx>0.001</ixx>
|
||||
<!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
|
||||
<ixy>0.0</ixy>
|
||||
<!-- for a box: ixy = 0 -->
|
||||
<ixz>0.0</ixz>
|
||||
<!-- for a box: ixz = 0 -->
|
||||
<iyy>0.001</iyy>
|
||||
<!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
|
||||
<iyz>0.0</iyz>
|
||||
<!-- for a box: iyz = 0 -->
|
||||
<izz>0.001</izz>
|
||||
<!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
|
||||
</inertia>
|
||||
</inertial>
|
||||
<inertial>
|
||||
<mass>0.001</mass>
|
||||
<inertia> <!-- inertias are tricky to compute -->
|
||||
<ixx>0.001</ixx>
|
||||
<!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
|
||||
<ixy>0.0</ixy>
|
||||
<!-- for a box: ixy = 0 -->
|
||||
<ixz>0.0</ixz>
|
||||
<!-- for a box: ixz = 0 -->
|
||||
<iyy>0.001</iyy>
|
||||
<!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
|
||||
<iyz>0.0</iyz>
|
||||
<!-- for a box: iyz = 0 -->
|
||||
<izz>0.001</izz>
|
||||
<!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://hokuyo_lidar/meshes/hokuyo.dae</uri>
|
||||
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<collision name="collision-base">
|
||||
<pose>0 0 -0.0145 0 0 0</pose>
|
||||
<geometry>
|
||||
|
@ -35,6 +37,7 @@
|
|||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<collision name="collision-top">
|
||||
<pose>0 0 0.0205 0 0 0</pose>
|
||||
<geometry>
|
||||
|
@ -44,34 +47,33 @@
|
|||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<sensor name="laser" type="ray">
|
||||
<pose>0.01 0 0.0175 0 -0 0</pose>
|
||||
<pose>0 0 0.0175 0 -0 0</pose>
|
||||
<ray>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>640</samples>
|
||||
<samples>512</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-3.14</min_angle>
|
||||
<max_angle>3.14</max_angle>
|
||||
<min_angle>-2.09</min_angle>
|
||||
<max_angle>2.09</max_angle>
|
||||
</horizontal>
|
||||
</scan>
|
||||
<range>
|
||||
<min>0.08</min>
|
||||
<max>10</max>
|
||||
<min>0.45</min>
|
||||
<max>5</max>
|
||||
<resolution>0.01</resolution>
|
||||
</range>
|
||||
</ray>
|
||||
|
||||
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
|
||||
<robotNamespace></robotNamespace>
|
||||
<topicName>scan</topicName>
|
||||
<frameName>laser_2d</frameName>
|
||||
</plugin>
|
||||
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
|
||||
<robotNamespace></robotNamespace>
|
||||
<topicName>scan</topicName>
|
||||
<frameName>laser</frameName>
|
||||
</plugin>
|
||||
<always_on>1</always_on>
|
||||
<update_rate>500</update_rate>
|
||||
<visualize>true</visualize>
|
||||
</sensor>
|
||||
|
||||
<visualize>True</visualize>
|
||||
</sensor>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
|
|
Loading…
Reference in New Issue