1<?xml version="1.0" ?> 2<!-- =================================================================================== --> 3<!-- | This document was autogenerated by xacro from wam_standalone.urdf.xacro | --> 4<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> 5<!-- =================================================================================== --> 6<robot name="wam" xmlns:xacro="http://www.ros.org/wiki/xacro"> 7 <link name="world"/> 8 <joint name="/j0" type="fixed"> 9 <parent link="world"/> 10 <child link="/wam_base"/> 11 <origin xyz="0 0 0" rpy="0 0 0" /> 12 </joint> 13 <link name="/wam_base"> 14 <visual> 15 <origin rpy="0 0 0" xyz="0 0 0"/> 16 <geometry> 17 <mesh filename="package://herb_description/meshes/wam/wam_base.dae"/> 18 </geometry> 19 <material name=""> 20 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 21 </material> 22 </visual> 23 <inertial> 24 <origin rpy="0 0 0" xyz="0.21556578 0.26189039 0.34533511"/> 25 <mass value="9.97059584"/> 26 <inertia ixx="0.10916849" ixy="0.00640270" ixz="0.02557874" iyx="0.00000000" iyy="0.18294303" iyz="0.00161433" izx="0.00000000" izy="0.00000000" izz="0.11760385"/> 27 </inertial> 28 <collision> 29 <geometry> 30 <mesh filename="package://herb_description/meshes/wam/wam_base_collision.STL"/> 31 </geometry> 32 </collision> 33 </link> 34 <link name="/wam1"> 35 <visual> 36 <origin rpy="0 0 0" xyz="0 0 0"/> 37 <geometry> 38 <mesh filename="package://herb_description/meshes/wam/wam1.dae"/> 39 </geometry> 40 <material name=""> 41 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 42 </material> 43 </visual> 44 <inertial> 45 <origin rpy="-1.570796 0 0" xyz="-0.004434 -0.000665 -0.121890"/> 46 <mass value="10.76768767"/> 47 <inertia ixx="0.13488033" ixy="-0.00213041" ixz="-0.00012485" iyx="0.00000000" iyy="0.11328369" iyz="0.00068555" izx="0.00000000" izy="0.00000000" izz="0.09046330"/> 48 </inertial> 49 <collision> 50 <geometry> 51 <mesh filename="package://herb_description/meshes/wam/wam1_collision.STL"/> 52 </geometry> 53 </collision> 54 </link> 55 <joint name="/j1" type="revolute"> 56 <origin rpy="-1.1127E-16 0 0" xyz="0.22 0.14 0.346"/> 57 <parent link="/wam_base"/> 58 <child link="/wam1"/> 59 <axis xyz="0 0 1"/> 60 <limit effort="1.8" lower="-2.6" upper="2.6" velocity="0.75"/> 61 </joint> 62 <link name="/wam2"> 63 <visual> 64 <origin rpy="0 0 0" xyz="0 0 0"/> 65 <geometry> 66 <mesh filename="package://herb_description/meshes/wam/wam2.dae"/> 67 </geometry> 68 <material name=""> 69 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 70 </material> 71 </visual> 72 <inertial> 73 <origin rpy="1.570796 0 0" xyz="-0.002370 -0.015421 0.031056"/> 74 <mass value="3.87493756"/> 75 <inertia ixx="0.02140958" ixy="0.00027172" ixz="0.00002461" iyx="0.00000000" iyy="0.01377875" iyz="-0.00181920" izx="0.00000000" izy="0.00000000" izz="0.01558906"/> 76 </inertial> 77 <collision> 78 <geometry> 79 <mesh filename="package://herb_description/meshes/wam/wam2_collision.STL"/> 80 </geometry> 81 </collision> 82 </link> 83 <joint name="/j2" type="revolute"> 84 <origin rpy="-1.5708 -4.0281E-16 -3.9443E-31" xyz="0 0 0"/> 85 <parent link="/wam1"/> 86 <child link="/wam2"/> 87 <axis xyz="0 0 1"/> 88 <limit effort="1.8" lower="-2.00" upper="2.00" velocity="0.75"/> 89 </joint> 90 <link name="/wam3"> 91 <visual> 92 <origin rpy="0 0 0" xyz="0 0 0"/> 93 <geometry> 94 <mesh filename="package://herb_description/meshes/wam/wam3.dae"/> 95 </geometry> 96 <material name=""> 97 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 98 </material> 99 </visual> 100 <inertial> 101 <origin rpy="-1.570796 0 0" xyz="0.006741 0.000033 0.342492"/> 102 <mass value="1.80228141"/> 103 <inertia ixx="0.05911077" ixy="-0.00249612" ixz="0.00000738" iyx="0.00000000" iyy="0.00324550" iyz="-0.00001767" izx="0.00000000" izy="0.00000000" izz="0.05927043"/> 104 </inertial> 105 <collision> 106 <geometry> 107 <mesh filename="package://herb_description/meshes/wam/wam3_collision.STL"/> 108 </geometry> 109 </collision> 110 </link> 111 <joint name="/j3" type="revolute"> 112 <origin rpy="1.5708 -3.9443E-31 4.0281E-16" xyz="0 0 0"/> 113 <parent link="/wam2"/> 114 <child link="/wam3"/> 115 <axis xyz="0 0 1"/> 116 <limit effort="1.8" lower="-2.80" upper="2.80" velocity="2.0"/> 117 </joint> 118 <link name="/wam4"> 119 <visual> 120 <origin rpy="0 0 0" xyz="0 0 0"/> 121 <geometry> 122 <mesh filename="package://herb_description/meshes/wam/wam4.dae"/> 123 </geometry> 124 <material name=""> 125 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 126 </material> 127 </visual> 128 <inertial> 129 <origin rpy="1.570796 0 0" xyz="-0.040015 -0.132717 -0.000229"/> 130 <mass value="2.40016804"/> 131 <inertia ixx="0.01491672" ixy="0.00001741" ixz="-0.00150604" iyx="0.00000000" iyy="0.01482922" iyz="-0.00002109" izx="0.00000000" izy="0.00000000" izz="0.00294463"/> 132 </inertial> 133 <collision> 134 <geometry> 135 <mesh filename="package://herb_description/meshes/wam/wam4_collision.STL"/> 136 </geometry> 137 </collision> 138 </link> 139 <joint name="/j4" type="revolute"> 140 <origin rpy="-1.5708 0 0" xyz="0.045 0 0.55"/> 141 <parent link="/wam3"/> 142 <child link="/wam4"/> 143 <axis xyz="0 0 1"/> 144 <limit effort="1.6" lower="-0.90" upper="3.10" velocity="2.0"/> 145 </joint> 146 <link name="/wam5"> 147 <visual> 148 <origin rpy="0 0 0" xyz="0 0 0"/> 149 <geometry> 150 <mesh filename="package://herb_description/meshes/wam/wam5.dae"/> 151 </geometry> 152 <material name=""> 153 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 154 </material> 155 </visual> 156 <inertial> 157 <origin rpy="-1.570796 0 0" xyz="0.000089 0.004358 0.294888"/> 158 <mass value="0.12376019"/> 159 <inertia ixx="0.00005029" ixy="0.00000020" ixz="-0.00000005" iyx="0.00000000" iyy="0.00007582" iyz="-0.00000359" izx="0.00000000" izy="0.00000000" izz="0.00006270"/> 160 </inertial> 161 <collision> 162 <geometry> 163 <mesh filename="package://herb_description/meshes/wam/wam5_collision.STL"/> 164 </geometry> 165 </collision> 166 </link> 167 <joint name="/j5" type="revolute"> 168 <origin rpy="1.5708 0 0" xyz="-0.045 0 0"/> 169 <parent link="/wam4"/> 170 <child link="/wam5"/> 171 <axis xyz="0 0 1"/> 172 <limit effort="0.6" lower="-4.76" upper="1.24" velocity="2.5"/> 173 </joint> 174 <link name="/wam6"> 175 <visual> 176 <origin rpy="0 0 0" xyz="0 0 0"/> 177 <geometry> 178 <mesh filename="package://herb_description/meshes/wam/wam6.dae"/> 179 </geometry> 180 <material name=""> 181 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 182 </material> 183 </visual> 184 <inertial> 185 <origin rpy="1.570796 0 0" xyz="-0.000123 -0.024683 -0.017032"/> 186 <mass value="0.41797364"/> 187 <inertia ixx="0.00055516" ixy="0.00000061" ixz="-0.00000074" iyx="0.00000000" iyy="0.00024367" iyz="-0.00004590" izx="0.00000000" izy="0.00000000" izz="0.00045358"/> 188 </inertial> 189 <collision> 190 <geometry> 191 <mesh filename="package://herb_description/meshes/wam/wam6_collision.STL"/> 192 </geometry> 193 </collision> 194 </link> 195 <joint name="/j6" type="revolute"> 196 <origin rpy="-1.5708 0 0" xyz="0 0 0.3"/> 197 <parent link="/wam5"/> 198 <child link="/wam6"/> 199 <axis xyz="0 0 1"/> 200 <limit effort="0.6" lower="-1.60" upper="1.60" velocity="2.5"/> 201 </joint> 202 <link name="/wam7"> 203 <visual> 204 <origin rpy="0 0 0" xyz="0 0 0"/> 205 <geometry> 206 <mesh filename="package://herb_description/meshes/wam/wam7.dae"/> 207 </geometry> 208 <material name=""> 209 <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1"/> 210 </material> 211 </visual> 212 <inertial> 213 <origin rpy="0 0 0" xyz="-0.000080 0.000163 0.056764"/> 214 <mass value="0.06864753"/> 215 <inertia ixx="0.00003773" ixy="-0.00000019" ixz="0.00000000" iyx="0.00000000" iyy="0.00003806" iyz="0.00000000" izx="0.00000000" izy="0.00000000" izz="0.00007408"/> 216 </inertial> 217 <collision> 218 <geometry> 219 <mesh filename="package://herb_description/meshes/wam/wam7_collision.STL"/> 220 </geometry> 221 </collision> 222 </link> 223 <joint name="/j7" type="revolute"> 224 <origin rpy="1.5708 0 0" xyz="0 0 0"/> 225 <parent link="/wam6"/> 226 <child link="/wam7"/> 227 <axis xyz="0 0 1"/> 228 <limit effort="0.174" lower="-3.00" upper="3.00" velocity="2.5"/> 229 </joint> 230</robot> 231