sonar_sensor.urdf.xacro 2.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768
  1. <?xml version="1.0"?>
  2. <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  3. <xacro:macro name="sonar_sensor" params="name parent *origin ros_topic update_rate min_range max_range field_of_view ray_count">
  4. <joint name="${name}_joint" type="fixed">
  5. <xacro:insert_block name="origin" />
  6. <parent link="${parent}"/>
  7. <child link="${name}_link"/>
  8. </joint>
  9. <link name="${name}_link">
  10. <inertial>
  11. <mass value="0.001" />
  12. <origin xyz="0 0 0" rpy="0 0 0" />
  13. <inertia ixx="0.000000017" ixy="0" ixz="0" iyy="0.000000017" iyz="0" izz="0.000000017" />
  14. </inertial>
  15. <visual>
  16. <origin xyz="0 0 0" rpy="0 0 0" />
  17. <geometry>
  18. <!--<box size="0.01 0.01 0.01" /> -->
  19. <mesh filename="package://hector_sensors_description/meshes/sonar_sensor/max_sonar_ez4.dae"/>
  20. </geometry>
  21. </visual>
  22. <collision>
  23. <origin xyz="0 0 0" rpy="0 0 0" />
  24. <geometry>
  25. <box size="0.01 0.01 0.01" />
  26. </geometry>
  27. </collision>
  28. </link>
  29. <gazebo reference="${name}_link">
  30. <sensor type="ray" name="${name}">
  31. <always_on>true</always_on>
  32. <update_rate>${update_rate}</update_rate>
  33. <pose>0 0 0 0 0 0</pose>
  34. <visualize>false</visualize>
  35. <ray>
  36. <scan>
  37. <horizontal>
  38. <samples>${ray_count}</samples>
  39. <resolution>1</resolution>
  40. <min_angle>-${field_of_view/2}</min_angle>
  41. <max_angle> ${field_of_view/2}</max_angle>
  42. </horizontal>
  43. <vertical>
  44. <samples>${ray_count}</samples>
  45. <resolution>1</resolution>
  46. <min_angle>-${field_of_view/2}</min_angle>
  47. <max_angle> ${field_of_view/2}</max_angle>
  48. </vertical>
  49. </scan>
  50. <range>
  51. <min>${min_range}</min>
  52. <max>${max_range}</max>
  53. <resolution>0.01</resolution>
  54. </range>
  55. </ray>
  56. <plugin name="gazebo_ros_${name}_controller" filename="libhector_gazebo_ros_sonar.so">
  57. <gaussianNoise>0.005</gaussianNoise>
  58. <topicName>${ros_topic}</topicName>
  59. <frameId>${name}_link</frameId>
  60. </plugin>
  61. </sensor>
  62. </gazebo>
  63. </xacro:macro>
  64. </robot>