123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167 |
- <?xml version="1.0"?>
- <robot>
- <property name="M_PI" value="3.14159"/>
- <property name="M_SCALE" value="0.001"/>
- <macro name="turtlebot_spacer" params="parent number x_loc y_loc z_loc">
- <joint name="spacer_${number}_joint" type="fixed">
- <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
- <parent link="${parent}"/>
- <child link="spacer_${number}_link" />
- </joint>
- <link name="spacer_${number}_link">
- <inertial>
- <mass value="0.00001" />
- <origin xyz="0 0 0" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0"
- iyy="1.0" iyz="0.0"
- izz="1.0" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <mesh filename="package://rbx1_description/meshes/68-02403-125_Spacer.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}" />
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <cylinder length="0.003175" radius=".0127"/>
- </geometry>
- </collision>
- </link>
- </macro>
- <macro name="turtlebot_standoff_1in" params="parent number x_loc y_loc z_loc">
- <joint name="standoff_1in_${number}_joint" type="fixed">
- <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
- <parent link="${parent}"/>
- <child link="standoff_1in_${number}_link" />
- </joint>
- <link name="standoff_1in_${number}_link">
- <inertial>
- <mass value="0.00001" />
- <origin xyz="0 0 0" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0"
- iyy="1.0" iyz="0.0"
- izz="1.0" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <mesh filename="package://rbx1_description/meshes/68-04552-1000-RA_Turtlebot_M-F_Standoff.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <cylinder length="0.0381" radius="0.011113"/>
- </geometry>
- </collision>
- </link>
- </macro>
- <macro name="turtlebot_standoff_2in" params="parent number x_loc y_loc z_loc">
- <joint name="standoff_2in_${number}_joint" type="fixed">
- <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
- <parent link="${parent}"/>
- <child link="standoff_2in_${number}_link" />
- </joint>
- <link name="standoff_2in_${number}_link">
- <inertial>
- <mass value="0.00001" />
- <origin xyz="0 0 0" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0"
- iyy="1.0" iyz="0.0"
- izz="1.0" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <mesh filename="package://rbx1_description/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <cylinder length="0.0635" radius="0.0381"/>
- </geometry>
- </collision>
- </link>
- </macro>
-
- <macro name="turtlebot_standoff_3in" params="parent number x_loc y_loc z_loc">
- <joint name="standoff_3in_${number}_joint" type="fixed">
- <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
- <parent link="${parent}"/>
- <child link="standoff_3in_${number}_link" />
- </joint>
- <link name="standoff_3in_${number}_link">
- <inertial>
- <mass value="0.00001" />
- <origin xyz="0 0 0" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0"
- iyy="1.0" iyz="0.0"
- izz="1.0" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <mesh filename="package://rbx1_description/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE*1.5}"/>
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <cylinder length="0.075" radius="0.0381"/>
- </geometry>
- </collision>
- </link>
- </macro>
- <macro name="turtlebot_standoff_8in" params="parent number x_loc y_loc z_loc">
- <joint name="standoff_8in_${number}_joint" type="fixed">
- <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
- <parent link="${parent}"/>
- <child link="standoff_8in_${number}_link" />
- </joint>
- <link name="standoff_8in_${number}_link">
- <inertial>
- <mass value="0.00001" />
- <origin xyz="0 0 0" />
- <inertia ixx="1.0" ixy="0.0" ixz="0.0"
- iyy="1.0" iyz="0.0"
- izz="1.0" />
- </inertial>
- <visual>
- <origin xyz=" 0 0 0 " rpy="0 0 0" />
- <geometry>
- <mesh filename="package://rbx1_description/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
- </geometry>
- </visual>
- <collision>
- <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
- <geometry>
- <cylinder length="0.2032" radius="0.011113"/>
- </geometry>
- </collision>
- </link>
- </macro>
- </robot>
|