vlp16_mount.urdf.xacro.xml 2.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980
  1. <?xml version="1.0"?>
  2. <robot
  3. xmlns:xacro="http://www.ros.org/wiki/xacro" name="hector_multisensor_head">
  4. <xacro:include filename="$(find hector_xacro_tools)/urdf/inertia_tensors.urdf.xacro"/>
  5. <xacro:include filename="$(find hector_sensors_description)/urdf/vlp16.urdf.xacro" />
  6. <xacro:include filename="$(find hector_xacro_tools)/urdf/joint_macros.urdf.xacro" />
  7. <xacro:property name="M_PI" value="3.14159265359"/>
  8. <xacro:macro name="spinning_sensor_mount_macro" params="parent name scaling has_geom:='true' use_gpu_lidar:='false' *origin">
  9. <joint name="${name}_joint_fixed" type="fixed">
  10. <xacro:insert_block name="origin"/>
  11. <parent link="${parent}" />
  12. <child link="${name}_mount_link_fixed"/>
  13. </joint>
  14. <link name="${name}_mount_link_fixed">
  15. </link>
  16. <joint name="${name}_spin_joint" type="continuous">
  17. <xacro:insert_block name="origin"/>
  18. <parent link="${parent}" />
  19. <child link="${name}_mount_link" />
  20. <axis xyz=" 0 0 1" />
  21. <limit effort="1000" velocity="100" />
  22. <joint_properties damping="500.0" friction="200.0" />
  23. </joint>
  24. <link name="${name}_mount_link">
  25. <xacro:if value="${has_geom}">
  26. <visual>
  27. <origin rpy="0 0 ${M_PI}" xyz="0 0 -0.21803"/>
  28. <geometry>
  29. <mesh filename="package://hector_components_description/meshes/autonomy_box/visionbox_lidar_mount_only.stl" scale="0.001 0.001 0.001" />
  30. </geometry>
  31. <material name="Grey">
  32. <color rgba="0.5 0.5 0.5 1"/>
  33. </material>
  34. </visual>
  35. </xacro:if>
  36. <xacro:inertial_sphere_with_pose mass="0.1" diameter="0.03">
  37. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  38. </xacro:inertial_sphere_with_pose>
  39. </link>
  40. <xacro:vlp16_advanced_parameters name="${name}_laser" parent="${name}_mount_link" ros_topic="/${name}/vlp16" update_rate="10" horizontal_samples="512" vertical_samples="8" min_range="0.1" max_range="100" use_gpu="${use_gpu_lidar}">
  41. <xacro:insert_block name="vlp16_calibration" />
  42. </xacro:vlp16_advanced_parameters>
  43. <xacro:joint_standard_transmission name="${name}_spin_joint"/>
  44. <gazebo reference="${name}_spin_joint">
  45. <implicitSpringDamper>1</implicitSpringDamper>
  46. </gazebo>
  47. <gazebo>
  48. <!-- ros_control plugin -->
  49. <plugin name="gazebo_ros_control_select_joints" filename="libgazebo_ros_control_select_joints.so">
  50. <robotNamespace>${name}_control</robotNamespace>
  51. <joints>${name}_spin_joint</joints>
  52. </plugin>
  53. </gazebo>
  54. <xacro:if value="${has_geom}">
  55. <gazebo reference="${name}_mount_link">
  56. <visual>
  57. <material>
  58. <ambient>0.1 0.1 0.1 1</ambient>
  59. <diffuse>0.48 0.48 0.48 1</diffuse>
  60. <emissive>0.237 0.237 0.237 1</emissive>
  61. <specular>0.8 0.8 0.8 1</specular>
  62. </material>
  63. </visual>
  64. </gazebo>
  65. </xacro:if>
  66. </xacro:macro>
  67. </robot>