123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869 |
- <?xml version="1.0"?>
- <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="lidar">
- <xacro:macro name="lidar" params="prefix:=laser">
- <!-- Create laser reference frame -->
- <link name="${prefix}_link">
- <inertial>
- <mass value="0.001" />
- <origin xyz="0 0 0" />
- <inertia ixx="0.001" ixy="0.0" ixz="0.0"
- iyy="0.001" iyz="0.0"
- izz="0.001" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <cylinder length="0.05" radius="0.05"/>
- </geometry>
- <material name="tire_mat"/>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <cylinder length="0.06" radius="0.05"/>
- </geometry>
- </collision>
- </link>
- <gazebo reference="${prefix}_link">
- <material>Gazebo/Black</material>
- </gazebo>
- <gazebo reference="${prefix}_link">
- <sensor type="ray" name="ls01g">
- <pose>0 0 0 0 0 0</pose>
- <visualize>false</visualize>
- <update_rate>10.0</update_rate>
- <ray>
- <scan>
- <horizontal>
- <samples>360</samples>
- <resolution>1</resolution>
- <min_angle>-3.1415926</min_angle>
- <max_angle>3.1415926</max_angle>
- </horizontal>
- </scan>
- <range>
- <min>0.10</min>
- <max>8.0</max>
- <resolution>0.01</resolution>
- </range>
- <noise>
- <type>gaussian</type>
- <mean>0.0</mean>
- <stddev>0.01</stddev> <!-- 雷达的噪声模拟 默认是0.01 -->
- </noise>
- </ray>
- <plugin name="gazebo_ls01g" filename="libgazebo_ros_laser.so">
- <topicName>/scan</topicName>
- <frameName>laser_link</frameName>
- </plugin>
- </sensor>
- </gazebo>
- </xacro:macro>
- <xacro:lidar prefix="laser"/>
- </robot>
|