lidar.xacro 2.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869
  1. <?xml version="1.0"?>
  2. <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="lidar">
  3. <xacro:macro name="lidar" params="prefix:=laser">
  4. <!-- Create laser reference frame -->
  5. <link name="${prefix}_link">
  6. <inertial>
  7. <mass value="0.001" />
  8. <origin xyz="0 0 0" />
  9. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  10. iyy="0.001" iyz="0.0"
  11. izz="0.001" />
  12. </inertial>
  13. <visual>
  14. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  15. <geometry>
  16. <cylinder length="0.05" radius="0.05"/>
  17. </geometry>
  18. <material name="tire_mat"/>
  19. </visual>
  20. <collision>
  21. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  22. <geometry>
  23. <cylinder length="0.06" radius="0.05"/>
  24. </geometry>
  25. </collision>
  26. </link>
  27. <gazebo reference="${prefix}_link">
  28. <material>Gazebo/Black</material>
  29. </gazebo>
  30. <gazebo reference="${prefix}_link">
  31. <sensor type="ray" name="ls01g">
  32. <pose>0 0 0 0 0 0</pose>
  33. <visualize>false</visualize>
  34. <update_rate>10.0</update_rate>
  35. <ray>
  36. <scan>
  37. <horizontal>
  38. <samples>360</samples>
  39. <resolution>1</resolution>
  40. <min_angle>-3.1415926</min_angle>
  41. <max_angle>3.1415926</max_angle>
  42. </horizontal>
  43. </scan>
  44. <range>
  45. <min>0.10</min>
  46. <max>8.0</max>
  47. <resolution>0.01</resolution>
  48. </range>
  49. <noise>
  50. <type>gaussian</type>
  51. <mean>0.0</mean>
  52. <stddev>0.01</stddev> <!-- 雷达的噪声模拟 默认是0.01 -->
  53. </noise>
  54. </ray>
  55. <plugin name="gazebo_ls01g" filename="libgazebo_ros_laser.so">
  56. <topicName>/scan</topicName>
  57. <frameName>laser_link</frameName>
  58. </plugin>
  59. </sensor>
  60. </gazebo>
  61. </xacro:macro>
  62. <xacro:lidar prefix="laser"/>
  63. </robot>