Files
scout_ros/scout_robot/urdf/scout.gazebo
2020-04-13 14:11:23 +08:00

71 lines
1.9 KiB
XML
Executable File

<?xml version="1.0"?>
<robot>
<!-- materials -->
<gazebo reference="base_link">
<material>Gazebo/While</material>
</gazebo>
<gazebo reference="front left_Link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="back left_Link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="front right_Link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="back right_Link">
<material>Gazebo/Black</material>
</gazebo>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/robot</robotNamespace>
</plugin>
</gazebo>
<!-- hokuyo -->
<gazebo reference="hokuyo_link">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<!-- Noise parameters based on published spec for Hokuyo laser
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
reading. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>hokuyo_link</frameName>
</plugin>
</sensor>
</gazebo>
</robot>