Go2Py_SIM/Go2Py/assets/urdf/go2_with_arm.urdf

1133 lines
29 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from go2_description.urdf | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by
Stephen Brawner (brawner@gmail.com)
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot name="go2">
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="0.021112 0 -0.005366"/>
<mass value="6.921"/>
<inertia ixx="0.02448" ixy="0.00012166" ixz="0.0014849" iyy="0.098077" iyz="-3.12E-05" izz="0.107"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/base.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.3762 0.0935 0.154"/>
</geometry>
</collision>
</link>
<link name="Head_upper">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.09" radius="0.05"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="Head_upper_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.285 0 0.01"/>
<parent link="base_link"/>
<child link="Head_upper"/>
<axis xyz="0 0 0"/>
</joint>
<link name="Head_lower">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.047"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="Head_lower_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.008 0 -0.07"/>
<parent link="Head_upper"/>
<child link="Head_lower"/>
<axis xyz="0 0 0"/>
</joint>
<link name="FL_HAA">
<inertial>
<origin rpy="0 0 0" xyz="-0.0054 0.00194 -0.000105"/>
<mass value="0.678"/>
<inertia ixx="0.00048" ixy="-3.01E-06" ixz="1.11E-06" iyy="0.000884" iyz="-1.42E-06" izz="0.000596"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/hip.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision> -->
</link>
<joint name="FL_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1934 0.0465 0"/>
<parent link="base_link"/>
<child link="FL_HAA"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint>
<link name="FL_HFE">
<inertial>
<origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/>
<mass value="1.152"/>
<inertia ixx="0.00584" ixy="8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/thigh.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<joint name="FL_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.0955 0"/>
<parent link="FL_HAA"/>
<child link="FL_HFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
</joint>
<link name="FL_KFE">
<inertial>
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
<mass value="0.154"/>
<inertia ixx="0.00108" ixy="3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="8.28E-06" izz="3.29E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/calf.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 -0.21 0" xyz="0.008 0 -0.06"/>
<geometry>
<cylinder length="0.12" radius="0.012"/>
</geometry>
</collision>
</link>
<joint name="FL_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FL_HFE"/>
<child link="FL_KFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint>
<link name="FL_KFElower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.065" radius="0.011"/>
</geometry>
</collision>
</link>
<joint name="FL_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="FL_KFE"/>
<child link="FL_KFElower"/>
<axis xyz="0 0 0"/>
</joint>
<link name="FL_KFElower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.03" radius="0.0155"/>
</geometry>
</collision>
</link>
<joint name="FL_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="FL_KFElower"/>
<child link="FL_KFElower1"/>
<axis xyz="0 0 0"/>
</joint>
<link name="FL_FOOT">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/foot.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0"/>
<geometry>
<sphere radius="0.022"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="FL_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FL_KFE"/>
<child link="FL_FOOT"/>
<axis xyz="0 0 0"/>
</joint>
<link name="FR_HAA">
<inertial>
<origin rpy="0 0 0" xyz="-0.0054 -0.00194 -0.000105"/>
<mass value="0.678"/>
<inertia ixx="0.00048" ixy="3.01E-06" ixz="1.11E-06" iyy="0.000884" iyz="1.42E-06" izz="0.000596"/>
</inertial>
<visual>
<origin rpy="3.1415 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/hip.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision> -->
</link>
<joint name="FR_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1934 -0.0465 0"/>
<parent link="base_link"/>
<child link="FR_HAA"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint>
<link name="FR_HFE">
<inertial>
<origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/>
<mass value="1.152"/>
<inertia ixx="0.00584" ixy="-8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/thigh_mirror.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<joint name="FR_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0955 0"/>
<parent link="FR_HAA"/>
<child link="FR_HFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.5708" upper="3.4907" velocity="30.1"/>
</joint>
<link name="FR_KFE">
<inertial>
<origin rpy="0 0 0" xyz="0.00548 0.000975 -0.115"/>
<mass value="0.154"/>
<inertia ixx="0.00108" ixy="-3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="-8.28E-06" izz="3.29E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/calf_mirror.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 -0.2 0" xyz="0.01 0 -0.06"/>
<geometry>
<cylinder length="0.12" radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="FR_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FR_HFE"/>
<child link="FR_KFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint>
<link name="FR_KFElower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.065" radius="0.011"/>
</geometry>
</collision>
</link>
<joint name="FR_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="FR_KFE"/>
<child link="FR_KFElower"/>
<axis xyz="0 0 0"/>
</joint>
<link name="FR_KFElower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.03" radius="0.0155"/>
</geometry>
</collision>
</link>
<joint name="FR_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="FR_KFElower"/>
<child link="FR_KFElower1"/>
<axis xyz="0 0 0"/>
</joint>
<link name="FR_FOOT">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/foot.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0"/>
<geometry>
<sphere radius="0.022"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="FR_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="FR_KFE"/>
<child link="FR_FOOT"/>
<axis xyz="0 0 0"/>
</joint>
<link name="HL_HAA">
<inertial>
<origin rpy="0 0 0" xyz="0.0054 0.00194 -0.000105"/>
<mass value="0.678"/>
<inertia ixx="0.00048" ixy="3.01E-06" ixz="-1.11E-06" iyy="0.000884" iyz="-1.42E-06" izz="0.000596"/>
</inertial>
<visual>
<origin rpy="0 3.1415 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/hip.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.08 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision> -->
</link>
<joint name="HL_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.1934 0.0465 0"/>
<parent link="base_link"/>
<child link="HL_HAA"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint>
<link name="HL_HFE">
<inertial>
<origin rpy="0 0 0" xyz="-0.00374 -0.0223 -0.0327"/>
<mass value="1.152"/>
<inertia ixx="0.00584" ixy="8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/thigh.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<joint name="HL_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.0955 0"/>
<parent link="HL_HAA"/>
<child link="HL_HFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-0.5236" upper="4.5379" velocity="30.1"/>
</joint>
<link name="HL_KFE">
<inertial>
<origin rpy="0 0 0" xyz="0.00548 -0.000975 -0.115"/>
<mass value="0.154"/>
<inertia ixx="0.00108" ixy="3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="8.28E-06" izz="3.29E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/calf.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 -0.2 0" xyz="0.01 0 -0.06"/>
<geometry>
<cylinder length="0.12" radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="HL_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="HL_HFE"/>
<child link="HL_KFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint>
<link name="HL_KFElower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.065" radius="0.011"/>
</geometry>
</collision>
</link>
<joint name="HL_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="HL_KFE"/>
<child link="HL_KFElower"/>
<axis xyz="0 0 0"/>
</joint>
<link name="HL_KFElower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.03" radius="0.0155"/>
</geometry>
</collision>
</link>
<joint name="HL_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="HL_KFElower"/>
<child link="HL_KFElower1"/>
<axis xyz="0 0 0"/>
</joint>
<link name="HL_FOOT">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/foot.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0"/>
<geometry>
<sphere radius="0.022"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="HL_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="HL_KFE"/>
<child link="HL_FOOT"/>
<axis xyz="0 0 0"/>
</joint>
<link name="HR_HAA">
<inertial>
<origin rpy="0 0 0" xyz="0.0054 -0.00194 -0.000105"/>
<mass value="0.678"/>
<inertia ixx="0.00048" ixy="-3.01E-06" ixz="-1.11E-06" iyy="0.000884" iyz="1.42E-06" izz="0.000596"/>
</inertial>
<visual>
<origin rpy="3.1415 3.1415 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/hip.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<!-- <collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.08 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision> -->
</link>
<joint name="HR_HAA_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.1934 -0.0465 0"/>
<parent link="base_link"/>
<child link="HR_HAA"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-1.0472" upper="1.0472" velocity="30.1"/>
</joint>
<link name="HR_HFE">
<inertial>
<origin rpy="0 0 0" xyz="-0.00374 0.0223 -0.0327"/>
<mass value="1.152"/>
<inertia ixx="0.00584" ixy="-8.72E-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/thigh_mirror.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1065"/>
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<joint name="HR_HFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0955 0"/>
<parent link="HR_HAA"/>
<child link="HR_HFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" lower="-0.5236" upper="4.5379" velocity="30.1"/>
</joint>
<link name="HR_KFE">
<inertial>
<origin rpy="0 0 0" xyz="0.00548 0.000975 -0.115"/>
<mass value="0.154"/>
<inertia ixx="0.00108" ixy="-3.4E-07" ixz="1.72E-05" iyy="0.0011" iyz="-8.28E-06" izz="3.29E-05"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/calf_mirror.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 -0.2 0" xyz="0.01 0 -0.06"/>
<geometry>
<cylinder length="0.12" radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="HR_KFE_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="HR_HFE"/>
<child link="HR_KFE"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="45.43" lower="-2.7227" upper="-0.83776" velocity="15.70"/>
</joint>
<link name="HR_KFElower">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.065" radius="0.011"/>
</geometry>
</collision>
</link>
<joint name="HR_KFElower_joint" type="fixed">
<origin rpy="0 0.05 0" xyz="0.020 0 -0.148"/>
<parent link="HR_KFE"/>
<child link="HR_KFElower"/>
<axis xyz="0 0 0"/>
</joint>
<link name="HR_KFElower1">
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.03" radius="0.0155"/>
</geometry>
</collision>
</link>
<joint name="HR_KFElower1_joint" type="fixed">
<origin rpy="0 0.48 0" xyz="-0.01 0 -0.04"/>
<parent link="HR_KFElower"/>
<child link="HR_KFElower1"/>
<axis xyz="0 0 0"/>
</joint>
<link name="HR_FOOT">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.04"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="go2_assets/dae/foot.dae"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.002 0 0"/>
<geometry>
<sphere radius="0.022"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="HR_FOOT_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.213"/>
<parent link="HR_KFE"/>
<child link="HR_FOOT"/>
<axis xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<origin rpy="0.001697 -0.020900 -0.000007" xyz="-0.027353 -0.005499 0.039913"/>
<parent link="base_link"/>
<child link="imu_link"/>
<axis xyz="0 0 0"/>
</joint>
<link name="utlidar">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="utlidar_joint" type="fixed">
<origin rpy="0 2.8782 0" xyz="0.28945 0 -0.046825"/>
<parent link="base_link"/>
<child link="utlidar"/>
<axis xyz="0 0 0"/>
</joint>
<link
name="d1_base_link">
<inertial>
<origin
xyz="-0.00048697 -2.9605E-12 0.017142"
rpy="0 0 0" />
<mass
value="0.077233" />
<inertia
ixx="0.00010316"
ixy="-1.0285E-14"
ixz="2.0449E-07"
iyy="0.00011888"
iyz="7.3026E-15"
izz="0.00018362" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint name="d1_base_joint" type="fixed">
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.05"/>
<parent link="base_link"/>
<child link="d1_base_link"/>
<axis xyz="0 0 0"/>
</joint>
<link
name="Link1">
<inertial>
<origin
xyz="0.0024649 0.00010517 0.032696"
rpy="0 0 0" />
<mass
value="0.13174" />
<inertia
ixx="6.7236E-05"
ixy="-5.5664E-08"
ixz="7.0454E-08"
iyy="5.416E-05"
iyz="-3.5709E-07"
izz="4.6637E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link1.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint
name="Joint1"
type="revolute">
<origin
xyz="0 0 0.0533"
rpy="0 0 -3.1416" />
<parent
link="d1_base_link" />
<child
link="Link1" />
<axis
xyz="0 0 1" />
<limit
lower="-2.35"
upper="2.35"
effort="0"
velocity="0" />
</joint>
<link
name="Link2">
<inertial>
<origin
xyz="0.0002018 0.19201 -0.027007"
rpy="0 0 0" />
<mass
value="0.20213" />
<inertia
ixx="0.00025682"
ixy="-1.139E-07"
ixz="5.5667E-08"
iyy="6.3307E-05"
iyz="-3.5717E-07"
izz="0.00022968" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link2.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint
name="Joint2"
type="revolute">
<origin
xyz="0 0.028 0.0563"
rpy="1.5708 0 -3.1416" />
<parent
link="Link1" />
<child
link="Link2" />
<axis
xyz="0 0 -1" />
<limit
lower="-1.57"
upper="1.57"
effort="0"
velocity="0" />
</joint>
<link
name="Link3">
<inertial>
<origin
xyz="0.015164 0.044482 -0.027461"
rpy="0 0 0" />
<mass
value="0.0629" />
<inertia
ixx="1.7232E-05"
ixy="-2.6967E-06"
ixz="-9.4911E-11"
iyy="1.2606E-05"
iyz="-9.9169E-11"
izz="1.4964E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link3.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint
name="Joint3"
type="revolute">
<origin
xyz="0 0.2693 0.0009"
rpy="0 0 0" />
<parent
link="Link2" />
<child
link="Link3" />
<axis
xyz="0 0 -1" />
<limit
lower="-1.57"
upper="1.57"
effort="0"
velocity="0" />
</joint>
<link
name="Link4">
<inertial>
<origin
xyz="-0.00029556 -0.00016104 0.091339"
rpy="0 0 0" />
<mass
value="0.083332" />
<inertia
ixx="3.9308E-05"
ixy="1.0126E-08"
ixz="-9.4316E-08"
iyy="3.4378E-05"
iyz="-1.6915E-09"
izz="1.1597E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link4.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint
name="Joint4"
type="revolute">
<origin
xyz="0.0577 0.042 -0.0275"
rpy="-1.5708 0 -1.5708" />
<parent
link="Link3" />
<child
link="Link4" />
<axis
xyz="0 0 1" />
<limit
lower="-2.35"
upper="2.35"
effort="0"
velocity="0" />
</joint>
<link
name="Link5">
<inertial>
<origin
xyz="0.040573 0.0062891 -0.023838"
rpy="0 0 0" />
<mass
value="0.053817" />
<inertia
ixx="1.3072E-05"
ixy="-3.9511E-07"
ixz="-3.1889E-10"
iyy="8.6301E-06"
iyz="-1.8416E-09"
izz="1.1049E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link5.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint
name="Joint5"
type="revolute">
<origin
xyz="-0.0001 -0.0237 0.14018"
rpy="1.5708 -1.5708 0" />
<parent
link="Link4" />
<child
link="Link5" />
<axis
xyz="0 0 -1" />
<limit
lower="-1.57"
upper="1.57"
effort="0"
velocity="0" />
</joint>
<link
name="Link6">
<inertial>
<origin
xyz="-0.0068528 -3.9973E-06 0.039705"
rpy="0 0 0" />
<mass
value="0.077892" />
<inertia
ixx="3.8236E-05"
ixy="1.3465E-08"
ixz="-2.0614E-07"
iyy="1.7707E-05"
iyz="-6.7117E-10"
izz="4.8839E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link6.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint
name="Joint6"
type="revolute">
<origin
xyz="0.0825 -0.0010782 -0.023822"
rpy="-1.5708 0 -1.5708" />
<parent
link="Link5" />
<child
link="Link6" />
<axis
xyz="0 0 -1" />
<limit
lower="-2.35"
upper="2.35"
effort="0"
velocity="0" />
</joint>
<link
name="Link7_1">
<inertial>
<origin
xyz="0.018927 0.006 0.012082"
rpy="0 0 0" />
<mass
value="0.015046" />
<inertia
ixx="1.2692E-06"
ixy="7.7441E-20"
ixz="-1.133E-07"
iyy="2.0229E-06"
iyz="1.2044E-20"
izz="2.6177E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link7_1.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link7_1.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint7_1"
type="prismatic">
<origin
xyz="-0.0056012 -0.029636 0.0706"
rpy="-1.5714 -1.5708 0" />
<parent
link="Link6" />
<child
link="Link7_1" />
<axis
xyz="0 0 -1" />
<limit
lower="0"
upper="0.03"
effort="0"
velocity="0" />
</joint>
<link
name="Link7_2">
<inertial>
<origin
xyz="0.018927 -0.006 0.012082"
rpy="0 0 0" />
<mass
value="0.015046" />
<inertia
ixx="1.2692E-06"
ixy="-7.8273E-20"
ixz="-1.133E-07"
iyy="2.0229E-06"
iyz="-1.2122E-20"
izz="2.6177E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link7_2.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="d1_assets/stl/Link7_2.STL" />
</geometry>
</collision>
</link>
<joint
name="Joint7_2"
type="prismatic">
<origin
xyz="-0.0056388 0.02964 0.0706"
rpy="1.5702 -1.5708 0" />
<parent
link="Link6" />
<child
link="Link7_2" />
<axis
xyz="0 0 1" />
<limit
lower="-0.03"
upper="0"
effort="0"
velocity="0" />
</joint>
</robot>