vlp16.urdf.xacro 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113
  1. <?xml version="1.0"?>
  2. <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  3. <xacro:include filename="$(find hector_xacro_tools)/urdf/inertia_tensors.urdf.xacro"/>
  4. <xacro:property name="M_PI" value="3.1415926535897931"/>
  5. <xacro:macro name="vlp16_model" params="name parent *origin">
  6. <joint name="${name}_joint" type="fixed">
  7. <xacro:insert_block name="origin"/>
  8. <parent link="${parent}"/>
  9. <child link="${name}_frame"/>
  10. </joint>
  11. <link name="${name}_frame">
  12. <xacro:inertial_sphere mass="0.83" diameter="0.1033"/>
  13. <visual>
  14. <origin xyz="0 0 -0.0378" rpy="${M_PI/2} 0 ${M_PI}"/>
  15. <geometry>
  16. <mesh filename="package://hector_sensors_description/meshes/vlp16/VLP16_base_1.dae" scale="0.001 0.001 0.001"/>
  17. </geometry>
  18. </visual>
  19. <visual>
  20. <origin xyz="0 0 -0.0378" rpy="${M_PI/2} 0 ${M_PI}"/>
  21. <geometry>
  22. <mesh filename="package://hector_sensors_description/meshes/vlp16/VLP16_base_2.dae" scale="0.001 0.001 0.001"/>
  23. </geometry>
  24. </visual>
  25. <visual>
  26. <origin xyz="0 0 -0.0378" rpy="${M_PI/2} 0 ${M_PI}"/>
  27. <geometry>
  28. <mesh filename="package://hector_sensors_description/meshes/vlp16/VLP16_scan.dae" scale="0.001 0.001 0.001"/>
  29. </geometry>
  30. </visual>
  31. <collision>
  32. <origin rpy="0 0 0" xyz="0 0 -0.00225"/>
  33. <geometry>
  34. <cylinder radius="0.0516" length="0.0717"/>
  35. </geometry>
  36. </collision>
  37. </link>
  38. </xacro:macro>
  39. <xacro:macro name="vlp16" params="name parent *origin ros_topic">
  40. <xacro:vlp16_advanced_parameters name="${name}" parent="${parent}" ros_topic="${ros_topic}" update_rate="10" horizontal_samples="512" vertical_samples="8" min_range="0.45" max_range="100">
  41. <xacro:insert_block name="origin"/>
  42. </xacro:vlp16_advanced_parameters>
  43. </xacro:macro>
  44. <xacro:macro name="vlp16_advanced_parameters" params="name parent *origin ros_topic update_rate horizontal_samples vertical_samples min_range max_range use_gpu:='false'">
  45. <xacro:vlp16_model name="${name}" parent="${parent}">
  46. <xacro:insert_block name="origin"/>
  47. </xacro:vlp16_model>
  48. <gazebo reference="${name}_frame">
  49. <xacro:if value="${use_gpu}">
  50. <xacro:property name="sensor_type" value="gpu_ray"/>
  51. <xacro:property name="gazebo_plugin_name" value="libgazebo_ros_velodyne_gpu_laser.so"/>
  52. </xacro:if >
  53. <xacro:unless value="${use_gpu}">
  54. <xacro:property name="sensor_type" value="ray"/>
  55. <xacro:property name="gazebo_plugin_name" value="libgazebo_ros_velodyne_laser.so"/>
  56. </xacro:unless>
  57. <sensor type="${sensor_type}" name="${name}-VLP16">
  58. <pose>0 0 0 0 0 0</pose>
  59. <visualize>false</visualize>
  60. <update_rate>${update_rate}</update_rate>
  61. <ray>
  62. <scan>
  63. <horizontal>
  64. <samples>${horizontal_samples}</samples>
  65. <resolution>1</resolution>
  66. <min_angle>-${M_PI}</min_angle>
  67. <max_angle>${M_PI}</max_angle>
  68. </horizontal>
  69. <vertical>
  70. <samples>${vertical_samples}</samples>
  71. <resolution>1</resolution>
  72. <min_angle>-${15.0*M_PI/180.0}</min_angle>
  73. <max_angle>${15.0*M_PI/180.0}</max_angle>
  74. </vertical>
  75. </scan>
  76. <range>
  77. <min>${min_range}</min>
  78. <max>${max_range}</max>
  79. <resolution>0.001</resolution>
  80. </range>
  81. <noise>
  82. <type>gaussian</type>
  83. <mean>0.0</mean>
  84. <stddev>0.0</stddev>
  85. </noise>
  86. </ray>
  87. <plugin name="gazebo_ros_laser_controller" filename="${gazebo_plugin_name}">
  88. <topicName>${ros_topic}</topicName>
  89. <frameName>${name}_frame</frameName>
  90. <min_range>${min_range}</min_range>
  91. <max_range>${max_range}</max_range>
  92. <gaussianNoise>0.008</gaussianNoise>
  93. </plugin>
  94. </sensor>
  95. </gazebo>
  96. </xacro:macro>
  97. </robot>