1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980 |
- <?xml version="1.0"?>
- <robot
- xmlns:xacro="http://www.ros.org/wiki/xacro" name="hector_multisensor_head">
- <xacro:include filename="$(find hector_xacro_tools)/urdf/inertia_tensors.urdf.xacro"/>
- <xacro:include filename="$(find hector_sensors_description)/urdf/vlp16.urdf.xacro" />
- <xacro:include filename="$(find hector_xacro_tools)/urdf/joint_macros.urdf.xacro" />
- <xacro:property name="M_PI" value="3.14159265359"/>
- <xacro:macro name="spinning_sensor_mount_macro" params="parent name scaling has_geom:='true' use_gpu_lidar:='false' *origin">
- <joint name="${name}_joint_fixed" type="fixed">
- <xacro:insert_block name="origin"/>
- <parent link="${parent}" />
- <child link="${name}_mount_link_fixed"/>
- </joint>
- <link name="${name}_mount_link_fixed">
- </link>
- <joint name="${name}_spin_joint" type="continuous">
- <xacro:insert_block name="origin"/>
- <parent link="${parent}" />
- <child link="${name}_mount_link" />
- <axis xyz=" 0 0 1" />
- <limit effort="1000" velocity="100" />
- <joint_properties damping="500.0" friction="200.0" />
- </joint>
- <link name="${name}_mount_link">
- <xacro:if value="${has_geom}">
- <visual>
- <origin rpy="0 0 ${M_PI}" xyz="0 0 -0.21803"/>
- <geometry>
- <mesh filename="package://hector_components_description/meshes/autonomy_box/visionbox_lidar_mount_only.stl" scale="0.001 0.001 0.001" />
- </geometry>
- <material name="Grey">
- <color rgba="0.5 0.5 0.5 1"/>
- </material>
- </visual>
- </xacro:if>
- <xacro:inertial_sphere_with_pose mass="0.1" diameter="0.03">
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- </xacro:inertial_sphere_with_pose>
- </link>
- <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}">
- <xacro:insert_block name="vlp16_calibration" />
- </xacro:vlp16_advanced_parameters>
- <xacro:joint_standard_transmission name="${name}_spin_joint"/>
- <gazebo reference="${name}_spin_joint">
- <implicitSpringDamper>1</implicitSpringDamper>
- </gazebo>
- <gazebo>
- <!-- ros_control plugin -->
- <plugin name="gazebo_ros_control_select_joints" filename="libgazebo_ros_control_select_joints.so">
- <robotNamespace>${name}_control</robotNamespace>
- <joints>${name}_spin_joint</joints>
- </plugin>
- </gazebo>
- <xacro:if value="${has_geom}">
- <gazebo reference="${name}_mount_link">
- <visual>
- <material>
- <ambient>0.1 0.1 0.1 1</ambient>
- <diffuse>0.48 0.48 0.48 1</diffuse>
- <emissive>0.237 0.237 0.237 1</emissive>
- <specular>0.8 0.8 0.8 1</specular>
- </material>
- </visual>
- </gazebo>
- </xacro:if>
- </xacro:macro>
- </robot>
|