|
| 1 | +<?xml version="1.0" ?> |
| 2 | +<!-- =================================================================================== --> |
| 3 | +<!-- | This document was autogenerated by xacro from xarm_device.urdf.xacro | --> |
| 4 | +<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> |
| 5 | +<!-- =================================================================================== --> |
| 6 | +<robot name="Lite6"> |
| 7 | + <!-- Insert at the beginning of xarm_device_macro.xacro --> |
| 8 | + <material name="Black"> |
| 9 | + <color rgba="0.0 0.0 0.0 1.0"/> |
| 10 | + </material> |
| 11 | + <material name="Red"> |
| 12 | + <color rgba="0.8 0.0 0.0 1.0"/> |
| 13 | + </material> |
| 14 | + <material name="White"> |
| 15 | + <color rgba="1.0 1.0 1.0 1.0"/> |
| 16 | + </material> |
| 17 | + <material name="Silver"> |
| 18 | + <color rgba="0.753 0.753 0.753 1.0"/> |
| 19 | + </material> |
| 20 | + <link name="world"/> |
| 21 | + <joint name="world_joint" type="fixed"> |
| 22 | + <parent link="world"/> |
| 23 | + <child link="link_base"/> |
| 24 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 25 | + </joint> |
| 26 | + <link name="link_base"> |
| 27 | + <inertial> |
| 28 | + <origin rpy="0 0 0" xyz="-0.00829544579053192 3.26357432323433E-05 0.0631194584987089"/> |
| 29 | + <mass value="1.65393501783165"/> |
| 30 | + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> |
| 31 | + </inertial> |
| 32 | + <visual> |
| 33 | + <geometry> |
| 34 | + <mesh filename="package://xarm_description/meshes/lite6/visual/link_base.stl"/> |
| 35 | + </geometry> |
| 36 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 37 | + <material name="White"/> |
| 38 | + </visual> |
| 39 | + <collision> |
| 40 | + <geometry> |
| 41 | + <mesh filename="package://xarm_description/meshes/lite6/collision/link_base.stl"/> |
| 42 | + </geometry> |
| 43 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 44 | + </collision> |
| 45 | + </link> |
| 46 | + <link name="link1"> |
| 47 | + <inertial> |
| 48 | + <origin rpy="0 0 0" xyz="-0.00036 0.04195 -0.0025"/> |
| 49 | + <mass value="1.411"/> |
| 50 | + <inertia ixx="0.0014516400000000001" ixy="-1.24e-05" ixz="6.7e-06" iyy="0.0008872999999999999" iyz="-0.0001255" izz="0.00131993"/> |
| 51 | + </inertial> |
| 52 | + <visual> |
| 53 | + <geometry> |
| 54 | + <mesh filename="package://xarm_description/meshes/lite6/visual/link1.stl"/> |
| 55 | + </geometry> |
| 56 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 57 | + <material name="White"/> |
| 58 | + </visual> |
| 59 | + <collision> |
| 60 | + <geometry> |
| 61 | + <mesh filename="package://xarm_description/meshes/lite6/collision/link1.stl"/> |
| 62 | + </geometry> |
| 63 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 64 | + </collision> |
| 65 | + </link> |
| 66 | + <joint name="joint1" type="revolute"> |
| 67 | + <origin rpy="0 0 0" xyz="0 0 0.2435"/> |
| 68 | + <parent link="link_base"/> |
| 69 | + <child link="link1"/> |
| 70 | + <axis xyz="0 0 1"/> |
| 71 | + <limit effort="50.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/> |
| 72 | + <dynamics damping="1.0" friction="1.0"/> |
| 73 | + </joint> |
| 74 | + <link name="link2"> |
| 75 | + <inertial> |
| 76 | + <origin rpy="0 0 0" xyz="0.179 0.0 0.0584"/> |
| 77 | + <mass value="1.34"/> |
| 78 | + <inertia ixx="0.0015854" ixy="6.766e-06" ixz="0.00115136" iyy="0.0056097" iyz="-1.1399999999999999e-06" izz="0.00485"/> |
| 79 | + </inertial> |
| 80 | + <visual> |
| 81 | + <geometry> |
| 82 | + <mesh filename="package://xarm_description/meshes/lite6/visual/link2.stl"/> |
| 83 | + </geometry> |
| 84 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 85 | + <material name="White"/> |
| 86 | + </visual> |
| 87 | + <collision> |
| 88 | + <geometry> |
| 89 | + <mesh filename="package://xarm_description/meshes/lite6/collision/link2.stl"/> |
| 90 | + </geometry> |
| 91 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 92 | + </collision> |
| 93 | + </link> |
| 94 | + <joint name="joint2" type="revolute"> |
| 95 | + <origin rpy="1.5708 -1.5708 3.1416" xyz="0 0 0"/> |
| 96 | + <parent link="link1"/> |
| 97 | + <child link="link2"/> |
| 98 | + <axis xyz="0 0 1"/> |
| 99 | + <limit effort="50.0" lower="-2.61799" upper="2.61799" velocity="3.14"/> |
| 100 | + <dynamics damping="1.0" friction="1.0"/> |
| 101 | + </joint> |
| 102 | + <link name="link3"> |
| 103 | + <inertial> |
| 104 | + <origin rpy="0 0 0" xyz="0.072 -0.0357 -0.001"/> |
| 105 | + <mass value="0.953"/> |
| 106 | + <inertia ixx="0.0008861" ixy="0.00039286999999999997" ixz="-7.065999999999999e-05" iyy="0.0015784999999999998" iyz="2.4449999999999998e-05" izz="0.00184677"/> |
| 107 | + </inertial> |
| 108 | + <visual> |
| 109 | + <geometry> |
| 110 | + <mesh filename="package://xarm_description/meshes/lite6/visual/link3.stl"/> |
| 111 | + </geometry> |
| 112 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 113 | + <material name="White"/> |
| 114 | + </visual> |
| 115 | + <collision> |
| 116 | + <geometry> |
| 117 | + <mesh filename="package://xarm_description/meshes/lite6/collision/link3.stl"/> |
| 118 | + </geometry> |
| 119 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 120 | + </collision> |
| 121 | + </link> |
| 122 | + <joint name="joint3" type="revolute"> |
| 123 | + <origin rpy="-3.1416 0 1.5708" xyz="0.2002 0 0"/> |
| 124 | + <parent link="link2"/> |
| 125 | + <child link="link3"/> |
| 126 | + <axis xyz="0 0 1"/> |
| 127 | + <limit effort="32.0" lower="-0.061087" upper="5.235988" velocity="3.14"/> |
| 128 | + <dynamics damping="1.0" friction="1.0"/> |
| 129 | + </joint> |
| 130 | + <link name="link4"> |
| 131 | + <inertial> |
| 132 | + <origin rpy="0 0 0" xyz="-0.002 -0.0285 -0.0813"/> |
| 133 | + <mass value="1.284"/> |
| 134 | + <inertia ixx="0.003705" ixy="2e-06" ixz="-7.17e-06" iyy="0.0030455" iyz="0.00093188" izz="0.0015412999999999998"/> |
| 135 | + </inertial> |
| 136 | + <visual> |
| 137 | + <geometry> |
| 138 | + <mesh filename="package://xarm_description/meshes/lite6/visual/link4.stl"/> |
| 139 | + </geometry> |
| 140 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 141 | + <material name="White"/> |
| 142 | + </visual> |
| 143 | + <collision> |
| 144 | + <geometry> |
| 145 | + <mesh filename="package://xarm_description/meshes/lite6/collision/link4.stl"/> |
| 146 | + </geometry> |
| 147 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 148 | + </collision> |
| 149 | + </link> |
| 150 | + <joint name="joint4" type="revolute"> |
| 151 | + <origin rpy="1.5708 0 0" xyz="0.087 -0.22761 0"/> |
| 152 | + <parent link="link3"/> |
| 153 | + <child link="link4"/> |
| 154 | + <axis xyz="0 0 1"/> |
| 155 | + <limit effort="32.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/> |
| 156 | + <dynamics damping="1.0" friction="1.0"/> |
| 157 | + </joint> |
| 158 | + <link name="link5"> |
| 159 | + <inertial> |
| 160 | + <origin rpy="0 0 0" xyz="0.0 0.01 0.0019"/> |
| 161 | + <mass value="0.804"/> |
| 162 | + <inertia ixx="0.0005667999999999999" ixy="-6e-07" ixz="5.299999999999999e-06" iyy="0.0005076999999999999" iyz="4.8e-07" izz="0.00053"/> |
| 163 | + </inertial> |
| 164 | + <visual> |
| 165 | + <geometry> |
| 166 | + <mesh filename="package://xarm_description/meshes/lite6/visual/link5.stl"/> |
| 167 | + </geometry> |
| 168 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 169 | + <material name="White"/> |
| 170 | + </visual> |
| 171 | + <collision> |
| 172 | + <geometry> |
| 173 | + <mesh filename="package://xarm_description/meshes/lite6/collision/link5.stl"/> |
| 174 | + </geometry> |
| 175 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 176 | + </collision> |
| 177 | + </link> |
| 178 | + <joint name="joint5" type="revolute"> |
| 179 | + <origin rpy="1.5708 0 0" xyz="0 0 0"/> |
| 180 | + <parent link="link4"/> |
| 181 | + <child link="link5"/> |
| 182 | + <axis xyz="0 0 1"/> |
| 183 | + <limit effort="32.0" lower="-2.1642" upper="2.1642" velocity="3.14"/> |
| 184 | + <dynamics damping="1.0" friction="1.0"/> |
| 185 | + </joint> |
| 186 | + <link name="link6"> |
| 187 | + <inertial> |
| 188 | + <origin rpy="0 0 0" xyz="0.0 -0.00194 -0.0102"/> |
| 189 | + <mass value="0.13"/> |
| 190 | + <inertia ixx="7.726e-05" ixy="-1e-06" ixz="-4e-07" iyy="8.5665e-05" iyz="6e-07" izz="0.00014813999999999997"/> |
| 191 | + </inertial> |
| 192 | + <visual> |
| 193 | + <geometry> |
| 194 | + <mesh filename="package://xarm_description/meshes/lite6/visual/link6.stl"/> |
| 195 | + </geometry> |
| 196 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 197 | + <material name="Silver"/> |
| 198 | + </visual> |
| 199 | + <collision> |
| 200 | + <geometry> |
| 201 | + <mesh filename="package://xarm_description/meshes/lite6/collision/link6.stl"/> |
| 202 | + </geometry> |
| 203 | + <origin rpy="0 0 0" xyz="0 0 0"/> |
| 204 | + </collision> |
| 205 | + </link> |
| 206 | + <joint name="joint6" type="revolute"> |
| 207 | + <origin rpy="-1.5708 0 0" xyz="0 0.0625 0"/> |
| 208 | + <parent link="link5"/> |
| 209 | + <child link="link6"/> |
| 210 | + <axis xyz="0 0 1"/> |
| 211 | + <limit effort="20.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.14"/> |
| 212 | + <dynamics damping="1.0" friction="1.0"/> |
| 213 | + </joint> |
| 214 | +</robot> |
| 215 | + |
0 commit comments