dual_hokuyo_mount.urdf.xacro.xml 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112
  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/hokuyo_utm30lx.urdf.xacro" />
  6. <xacro:property name="M_PI" value="3.14159265359"/>
  7. <xacro:macro name="spinning_sensor_mount_macro" params="parent name scaling *origin">
  8. <!-- <link name="${name}_link">
  9. <inertial>
  10. <mass value="0.8"/>
  11. <inertia ixx="0.0025" ixy="0.0" ixz="0.0001" iyy="0.0013" iyz="0.0" izz="0.0026"/>
  12. </inertial>
  13. <collision name="collision">
  14. <xacro:insert_block name="origin"/>
  15. <geometry>
  16. <mesh filename="package://hector_components_description/meshes/hector_multisensor_head/multisensor_head_collision.stl" scale="${scaling} ${scaling} ${scaling}"/>
  17. </geometry>
  18. </collision>
  19. <visual>
  20. <xacro:insert_block name="origin"/>
  21. <geometry>
  22. <mesh filename="package://hector_components_description/meshes/hector_multisensor_head/multisensor_head.stl" scale="${scaling} ${scaling} ${scaling}"/>
  23. </geometry>
  24. </visual>
  25. </link>-->
  26. <joint name="${name}_spin_joint_fixed" type="fixed">
  27. <!--<origin xyz="0.061 0.0 0.134" rpy="0 0 0"/>-->
  28. <xacro:insert_block name="origin"/>
  29. <parent link="${parent}" />
  30. <child link="${name}_lidar_mount_link_fixed"/>
  31. <axis xyz="1 0 0" rpy="0 0 0"/>
  32. </joint>
  33. <link name="${name}_lidar_mount_link_fixed">
  34. </link>
  35. <joint name="${name}_spin_joint" type="continuous">
  36. <!--<origin xyz="0.061 0.0 0.134" rpy="0 0 0"/>-->
  37. <xacro:insert_block name="origin"/>
  38. <parent link="${parent}" />
  39. <child link="${name}_lidar_mount_link" />
  40. <axis xyz=" 0 0 1" />
  41. <limit effort="1000" velocity="100" />
  42. <joint_properties damping="500.0" friction="200.0" />
  43. </joint>
  44. <link name="${name}_lidar_mount_link">
  45. <xacro:inertial_sphere_with_pose mass="0.1" diameter="0.03">
  46. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  47. </xacro:inertial_sphere_with_pose>
  48. <!-- Visualize collision cylinder
  49. <visual>
  50. <origin xyz="-0.01 0 0.01" rpy="0 ${M_PI/2} 0"/>
  51. <geometry>
  52. <cylinder radius="0.05" length="0.12" />
  53. </geometry>
  54. </visual>-->
  55. <!-- Visualize mesh data for checking LIDAR positioning-->
  56. <!--
  57. <visual>
  58. <origin xyz="-0.0 0 0.0" rpy="0 0 ${M_PI*0.5}"/>
  59. <geometry>
  60. <mesh filename="package://argo_tracker_description/meshes/argo_tracker_lidar_assembly.stl"/>
  61. </geometry>
  62. <material name="DarkGrey">
  63. <color rgba="0.3 0.3 0.3 1"/>
  64. </material>
  65. </visual>
  66. -->
  67. <collision>
  68. <origin xyz="0.0 0 0.08" rpy="0 0 0"/>
  69. <geometry>
  70. <cylinder radius="0.1" length="0.185" />
  71. </geometry>
  72. </collision>
  73. </link>
  74. <xacro:hokuyo_utm30lx name="${name}_pitch_hokuyo_laser" parent="${name}_lidar_mount_link" ros_topic="/spin_laser/pitch_scan_gazebo" update_rate="80" ray_count="1040" min_angle="-130" max_angle="130">
  75. <xacro:insert_block name="pitch_lidar_calibration" />
  76. </xacro:hokuyo_utm30lx>
  77. <xacro:hokuyo_utm30lx name="${name}_vertical_hokuyo_laser" parent="${name}_lidar_mount_link" ros_topic="/spin_laser/vertical_scan_gazebo" update_rate="80" ray_count="1040" min_angle="-130" max_angle="130">
  78. <xacro:insert_block name="vertical_lidar_calibration" />
  79. </xacro:hokuyo_utm30lx>
  80. <xacro:joint_standard_transmission name="${name}_spin_joint"/>
  81. <gazebo reference="${name}_spin_joint">
  82. <implicitSpringDamper>1</implicitSpringDamper>
  83. </gazebo>
  84. <gazebo>
  85. <!-- ros_control plugin -->
  86. <plugin name="gazebo_ros_control_select_joints" filename="libgazebo_ros_control_select_joints.so">
  87. <robotNamespace>spin_lidar_control</robotNamespace>
  88. <joints>spin_lidar_spin_joint</joints>
  89. </plugin>
  90. </gazebo>
  91. <!-- <xacro:asus_camera name="${name}_cam" parent="${name}_link">
  92. <origin xyz="0.065 0.0 0.23" rpy="0 0 0"/>
  93. </xacro:asus_camera> -->
  94. <!-- <gazebo reference="${name}_spinning_lidar_root_link"><material>Gazebo/Grey</material></gazebo><gazebo reference="${name}_spinning_lidar_spin_link"><material>Gazebo/Grey</material></gazebo> -->
  95. </xacro:macro>
  96. </robot>