12345678910111213141516171819202122232425262728293031323334353637383940414243444546 |
- <?xml version="1.0"?>
- <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="autonomy_box">
- <xacro:property name="M_PI" value="3.1415926535897931" />
- <!--<xacro:include filename="$(find hector_components_description)/urdf/vlp16_mount.urdf.xacro.xml"/>-->
- <xacro:include filename="$(find drz_telemax_description)/urdf/drz_telemax_navigation_module.urdf.xacro"/>
- <xacro:property name="autonomy_box_length" value="0.353"/>
- <xacro:property name="autonomy_box_width" value="0.24"/>
- <xacro:property name="autonomy_box_height" value="0.11"/>
- <xacro:macro name="autonomy_box" params="parent name scaling *origin">
- <joint name="${name}_joint_fixed" type="fixed">
- <xacro:insert_block name="origin"/>
- <parent link="${parent}"/>
- <child link="${name}_link"/>
- </joint>
- <link name="${name}_link">
- <origin xyz="0 0 0" rpy="0 0 0"/>
- <visual>
- <origin xyz="0 0 ${-autonomy_box_height/2}" rpy="${-M_PI/2} 0 ${M_PI}"/>
- <geometry>
- <mesh filename="package://drz_telemax_description/meshes/autonomy_box.dae" scale="0.001 0.001 0.001"/>
- </geometry>
- </visual>
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0"/>
- <geometry>
- <box size="${autonomy_box_length} ${autonomy_box_width} ${autonomy_box_height}"/>
- </geometry>
- </collision>
- </link>
- <joint name="imu_link_joint" type="fixed">
- <origin xyz="0.04 0.04 0.08" rpy="0 0 0"/>
- <parent link="${name}_link" />
- <child link="imu_link"/>
- </joint>
- <link name="imu_link">
- </link>
- <xacro:navigation_module parent="${name}_link" name="navigation_module" scaling="0.001">
- <origin xyz="${-autonomy_box_length/2 - 0.008 + navigation_module_length/2} 0 ${autonomy_box_height/2 + 0.011 - navigation_module_height/2}" rpy="0 0 0"/>
- </xacro:navigation_module>
- </xacro:macro>
- </robot>
|