-
Guilhem Saurel authoredGuilhem Saurel authored
poppy.urdf 28.67 KiB
<?xml version="1.0" encoding="utf-8"?>
<robot name="Poppy_Humanoid">
<link name="pelvis">
<inertial>
<origin xyz="-0.000134932459328483 -0.000399086261064929 0.00195556930608449" rpy="0 0 0"></origin>
<mass value="0.18520035953947"></mass>
<inertia ixx="0.000101804322229161" ixy="3.56589402562651E-08" ixz="-1.38613151054156E-05" iyy="0.000142404075398435" iyz="-3.50682832702007E-06" izz="9.38193247222871E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/pelvis_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/pelvis_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.18508</mass>
</link>
<link name="r_hip">
<inertial>
<origin xyz="-0.0419310610774408 0.0190565121211527 -0.0049369159749795" rpy="0 0 0"></origin>
<mass value="0.0843835237958419"></mass>
<inertia ixx="2.80785419197495E-05" ixy="-1.23046307113086E-06" ixz="6.6239556232755E-07" iyy="2.83383567782285E-05" iyz="-1.44609279432087E-06" izz="2.15931686710985E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_hip_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_hip_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.08433</mass>
</link>
<link name="r_hip_motor">
<inertial>
<origin xyz="0.00012677211714017 -0.0228896110294103 -0.0134988950219984" rpy="0 0 0"></origin>
<mass value="0.0831707898707576"></mass>
<inertia ixx="2.94087635631147E-05" ixy="-1.19904545841814E-08" ixz="-2.40263672865729E-07" iyy="3.59801748266375E-05" iyz="7.9755837503152E-07" izz="2.29200602273928E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_hip_motor_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_hip_motor_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.13848</mass>
</link>
<link name="r_thigh">
<inertial>
<origin xyz="0.0192501209789311 -0.140974172218775 0.000432765258959229" rpy="0 0 0"></origin>
<mass value="0.116386255838466"></mass>
<inertia ixx="0.000357762131890894" ixy="-4.71321103204108E-05" ixz="2.18885095933642E-06" iyy="5.14619739065129E-05" iyz="-5.54069244270054E-06" izz="0.000370171570432626"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_thigh_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_thigh_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.12066</mass>
</link>
<link name="r_shin">
<inertial>
<origin xyz="-0.00150809388022299 -0.137041584549603 0.0228988594303728" rpy="0 0 0"></origin>
<mass value="0.115582219792398"></mass>
<inertia ixx="0.000397225397723862" ixy="-1.73262609639968E-05" ixz="1.32921239310872E-08" iyy="3.98086710206889E-05" iyz="-5.89721905441721E-07" izz="0.000393657905933943"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_shin_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_shin_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.11169</mass>
</link>
<link name="r_foot">
<inertial>
<origin xyz="0.0204293303781304 -0.0233359048261193 0.0268526073213802" rpy="0 0 0"></origin>
<mass value="0.0467879950319091"></mass>
<inertia ixx="8.14403907813341E-05" ixy="1.79180509533517E-07" ixz="-2.42059026946486E-06" iyy="8.8648252995759E-05" iyz="-3.23018791598496E-06" izz="1.79463752431845E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_foot_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_foot_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.04674</mass>
</link>
<link name="l_hip">
<inertial>
<origin xyz="0.0419306472605077 0.0190563885809745 -0.00493699078761145" rpy="0 0 0"></origin>
<mass value="0.084384314388701"></mass>
<inertia ixx="2.80793467645287E-05" ixy="1.23086422338588E-06" ixz="-6.62398430684737E-07" iyy="2.83405782814578E-05" iyz="-1.44600299896268E-06" izz="2.15947433435168E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_hip_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_hip_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.08434</mass>
</link>
<link name="l_hip_motor">
<inertial>
<origin xyz="-0.000127079593402107 -0.0228896103855824 -0.0134988950219984" rpy="0 0 0"></origin>
<mass value="0.0831707898707576"></mass>
<inertia ixx="2.94087634441972E-05" ixy="1.14532470512781E-08" ixz="2.40221424306256E-07" iyy="3.59801683348766E-05" iyz="7.97560828147263E-07" izz="2.29200536167144E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_hip_motor_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_hip_motor_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.13848</mass>
</link>
<link name="l_thigh">
<inertial>
<origin xyz="-0.019252460356064 -0.142230931721003 0.000612323159069193" rpy="0 0 0"></origin>
<mass value="0.114854459344049"></mass>
<inertia ixx="0.000344974307251891" ixy="4.73949176309948E-05" ixz="-2.2011322605997E-06" iyy="5.11655383215627E-05" iyz="-3.3911468808746E-06" izz="0.000357718491831138"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_thigh_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_thigh_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.12152</mass>
</link>
<link name="l_shin">
<inertial>
<origin xyz="-0.00150809145543363 -0.137041584769234 -0.0229033576380381" rpy="0 0 0"></origin>
<mass value="0.11558221959692"></mass>
<inertia ixx="0.000397225344473892" ixy="-1.7326274763791E-05" ixz="-3.52146929156471E-09" iyy="3.98086215785412E-05" iyz="5.50111227416849E-07" izz="0.000393657903677591"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_shin_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_shin_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.11169</mass>
</link>
<link name="l_foot">
<inertial>
<origin xyz="-0.020427799658059 -0.023322293418243 0.0268332758297585" rpy="0 0 0"></origin>
<mass value="0.0468257348098641"></mass>
<inertia ixx="8.1463512692765E-05" ixy="-1.79215713282762E-07" ixz="2.42595321155028E-06" iyy="8.8658680494918E-05" iyz="-3.23538234039819E-06" izz="1.7963767676241E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_foot_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_foot_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.04678</mass>
</link>
<link name="abs_motors">
<inertial>
<origin xyz="-6.29779489192246E-05 0.0133591399673186 -0.0195687625589375" rpy="0 0 0"></origin>
<mass value="0.16766708386429"></mass>
<inertia ixx="0.000151720676825684" ixy="-2.41666285846992E-07" ixz="-2.06688911297549E-07" iyy="0.000131382009077746" iyz="-2.13904639264389E-06" izz="6.52732386194484E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/abs_motors_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/abs_motors_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.27838</mass>
</link>
<link name="abdomen">
<inertial>
<origin xyz="4.70358640929572E-07 0.0445314260459549 -0.022296044885406" rpy="0 0 0"></origin>
<mass value="0.0384110457457536"></mass>
<inertia ixx="5.9365236572053E-05" ixy="-8.257716306361E-11" ixz="-2.55036869156096E-10" iyy="5.98640694082658E-05" iyz="3.94818292640265E-07" izz="2.35987614893539E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/abdomen_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/abdomen_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.03839</mass>
</link>
<link name="spine">
<inertial>
<origin xyz="-2.40411891850495E-07 0.0288451667347867 -0.0100975118547382" rpy="0 0 0"></origin>
<mass value="0.0926815106655512"></mass>
<inertia ixx="3.84763910015325E-05" ixy="-1.20593001730888E-09" ixz="-2.38589260905183E-10" iyy="2.7320514654861E-05" iyz="1.47490149318973E-06" izz="3.26595211965373E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/spine_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/spine_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.09264</mass>
</link>
<link name="bust_motors">
<inertial>
<origin xyz="3.50872416629779E-05 0.0105220286877652 -0.0174331453843439" rpy="0 0 0"></origin>
<mass value="0.158876054570625"></mass>
<inertia ixx="0.000100953683249293" ixy="-3.89105307189684E-07" ixz="9.71749941401585E-08" iyy="8.94288410563621E-05" iyz="-1.31738255727689E-06" izz="4.26225972692235E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/bust_motors_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/bust_motors_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.15889</mass>
</link>
<link name="chest">
<inertial>
<origin xyz="2.35256459143538E-06 0.0514948183080913 -0.0105463056982622" rpy="0 0 0"></origin>
<mass value="0.262925523172723"></mass>
<inertia ixx="0.000154597294293882" ixy="2.32304239504647E-08" ixz="-2.47140128362103E-08" iyy="0.000750952782458072" iyz="1.53530143139102E-06" izz="0.000688549998744818"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/chest_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/chest_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.27528</mass>
</link>
<link name="neck">
<inertial>
<origin xyz="-0.00147486363077957 0.00928455262636602 2.89600749219313E-06" rpy="0 0 0"></origin>
<mass value="0.00588496516988365"></mass>
<inertia ixx="7.25596636570396E-07" ixy="-9.29944216419538E-08" ixz="2.01438227027406E-10" iyy="2.33535976458607E-06" iyz="1.55383710797264E-11" izz="2.57395421284165E-06"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/neck_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/neck_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.00588</mass>
</link>
<link name="head">
<inertial>
<origin xyz="0.000557544173188459 0.0327437693305889 -0.0132545775103434" rpy="0 0 0"></origin>
<mass value="0.188564323997503"></mass>
<inertia ixx="0.000353329921483274" ixy="-2.17595216032547E-07" ixz="4.10678991843685E-06" iyy="0.000384587155295662" iyz="-2.16656424152966E-05" izz="0.000396626339401006"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/head_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/head_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.2126</mass>
</link>
<link name="l_shoulder">
<inertial>
<origin xyz="0.0105246491971973 0.00179805316216127 -0.00915201992957032" rpy="0 0 0"></origin>
<mass value="0.00843598968780806"></mass>
<inertia ixx="3.39606863056539E-06" ixy="-4.79545875245114E-08" ixz="2.95435354929514E-08" iyy="3.56726082486902E-06" iyz="1.00382310579659E-08" izz="1.84634806401887E-06"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_shoulder_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_shoulder_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.00838</mass>
</link>
<link name="l_shoulder_motor">
<inertial>
<origin xyz="2.25562237481797E-07 0.0125756739553211 0.00859826040204853" rpy="0 0 0"></origin>
<mass value="0.0828144098443214"></mass>
<inertia ixx="2.76486208811411E-05" ixy="1.32207552337974E-10" ixz="6.6889770978984E-10" iyy="1.64427853426986E-05" iyz="7.23401723852699E-07" izz="2.26416351010788E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_shoulder_motor_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_shoulder_motor_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.08288</mass>
</link>
<link name="l_upper_arm">
<inertial>
<origin xyz="3.30518731642866E-05 0.0628256242231928 -0.0106376043749558" rpy="0 0 0"></origin>
<mass value="0.168140859572398"></mass>
<inertia ixx="0.000280827719319256" ixy="6.03218629893559E-07" ixz="3.24530722833658E-09" iyy="4.23293519917111E-05" iyz="3.11052764904881E-06" izz="0.000275916197869213"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_upper_arm_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_upper_arm_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.16814</mass>
</link>
<link name="l_forearm">
<inertial>
<origin xyz="0.00691480023011085 0.10715758721324 0.00499021473883754" rpy="0 0 0"></origin>
<mass value="0.0486512481725727"></mass>
<inertia ixx="0.000185803541823861" ixy="7.31763110936326E-06" ixz="-9.0080655878687E-08" iyy="1.51053240271383E-05" iyz="-1.35878077941956E-05" izz="0.000182745910584552"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_forearm_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/l_forearm_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.04863</mass>
</link>
<link name="r_shoulder">
<inertial>
<origin xyz="-0.0104970276721559 0.00172611065393897 -0.00916610067254806" rpy="0 0 0"></origin>
<mass value="0.00848189714003649"></mass>
<inertia ixx="3.40574097306283E-06" ixy="4.48540328143448E-08" ixz="-3.01046953764439E-08" iyy="3.57001060355875E-06" iyz="1.1601962064402E-08" izz="1.85571692853151E-06"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_shoulder_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_shoulder_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.00838</mass>
</link>
<link name="r_shoulder_motor">
<inertial>
<origin xyz="2.25562237481797E-07 0.0125756739553211 0.00859826040204864" rpy="0 0 0"></origin>
<mass value="0.0828144098443213"></mass>
<inertia ixx="2.76486208811411E-05" ixy="1.32207552352561E-10" ixz="6.68897709796528E-10" iyy="1.64427853426986E-05" iyz="7.23401723852708E-07" izz="2.26416351010787E-05"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_shoulder_motor_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_shoulder_motor_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.08288</mass>
</link>
<link name="r_upper_arm">
<inertial>
<origin xyz="-3.32548713521223E-05 0.0628256242258387 -0.0106376027333001" rpy="0 0 0"></origin>
<mass value="0.16814085957724"></mass>
<inertia ixx="0.000280827719414285" ixy="-6.03127767269455E-07" ixz="-3.86325402336742E-09" iyy="4.23293497956197E-05" iyz="3.11054354485249E-06" izz="0.00027591619563535"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_upper_arm_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_upper_arm_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.16814</mass>
</link>
<link name="r_forearm">
<inertial>
<origin xyz="-0.00691618587524222 0.107157908858058 0.00498983982891094" rpy="0 0 0"></origin>
<mass value="0.0486511084909604"></mass>
<inertia ixx="0.000185805096233415" ixy="-7.3225450436654E-06" ixz="9.10153472751173E-08" iyy="1.51060270748784E-05" iyz="-1.35866305828973E-05" izz="0.000182748555542486"></inertia>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_forearm_visual.STL"></mesh>
</geometry>
<material name="">
<color rgba="0.9 0.9 0.9 1.0"></color>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<geometry>
<mesh filename="package://meshes/r_forearm_respondable.STL"></mesh>
</geometry>
</collision>
<mass>0.04863</mass>
</link>
<joint name="r_hip_x" type="revolute">
<origin xyz="-0.0225417390633467 0 0" rpy="1.5707963267949 0 0"></origin>
<parent link="pelvis"></parent>
<child link="r_hip"></child>
<axis xyz="0 0 -1"></axis>
<limit effort="3.1" lower="-0.497418836818" upper="0.523598775598" velocity="7.0"></limit>
</joint>
<joint name="r_hip_z" type="revolute">
<origin xyz="-0.0439986111539757 0 0.005" rpy="0 0 0"></origin>
<parent link="r_hip"></parent>
<child link="r_hip_motor"></child>
<axis xyz="0 -1 0"></axis>
<limit effort="3.1" lower="-1.57079632679" upper="0.436332312999" velocity="7.0"></limit>
</joint>
<joint name="r_hip_y" type="revolute">
<origin xyz="0 -0.024 0" rpy="0 0 0"></origin>
<parent link="r_hip_motor"></parent>
<child link="r_thigh"></child>
<axis xyz="-1 0 0"></axis>
<limit effort="7.3" lower="-1.4835298642" upper="1.83259571459" velocity="8.2"></limit>
</joint>
<joint name="r_knee_y" type="revolute">
<origin xyz="0 -0.182 0" rpy="0 1.5707963267949 0"></origin>
<parent link="r_thigh"></parent>
<child link="r_shin"></child>
<axis xyz="0 0 -1"></axis>
<limit effort="3.1" lower="-2.33874119767" upper="0.0610865238198" velocity="7.0"></limit>
</joint>
<joint name="r_ankle_y" type="revolute">
<origin xyz="0 -0.18 0" rpy="0 -1.5708 0"></origin>
<parent link="r_shin"></parent>
<child link="r_foot"></child>
<axis xyz="-1 0 0"></axis>
<limit effort="3.1" lower="-0.785398163397" upper="0.785398163397" velocity="7.0"></limit>
</joint>
<joint name="l_hip_x" type="revolute">
<origin xyz="0.0225417390633466 0 0" rpy="1.5707963267949 0 0"></origin>
<parent link="pelvis"></parent>
<child link="l_hip"></child>
<axis xyz="0 0 -1"></axis>
<limit effort="3.1" lower="-0.523598775598" upper="0.497418836818" velocity="7.0"></limit>
</joint>
<joint name="l_hip_z" type="revolute">
<origin xyz="0.0439986111539757 0 0.005" rpy="0 0 0"></origin>
<parent link="l_hip"></parent>
<child link="l_hip_motor"></child>
<axis xyz="0 -1 0"></axis>
<limit effort="3.1" lower="-0.436332312999" upper="1.57079632679" velocity="7.0"></limit>
</joint>
<joint name="l_hip_y" type="revolute">
<origin xyz="0 -0.024 0" rpy="0 0 0"></origin>
<parent link="l_hip_motor"></parent>
<child link="l_thigh"></child>
<axis xyz="1 0 0"></axis>
<limit effort="7.3" lower="-1.81514242207" upper="1.46607657168" velocity="8.2"></limit>
</joint>
<joint name="l_knee_y" type="revolute">
<origin xyz="0 -0.182 0" rpy="0 1.5707963267949 0"></origin>
<parent link="l_thigh"></parent>
<child link="l_shin"></child>
<axis xyz="0 0 -1"></axis>
<limit effort="3.1" lower="-0.0610865238198" upper="2.33874119767" velocity="7.0"></limit>
</joint>
<joint name="l_ankle_y" type="revolute">
<origin xyz="0 -0.18 0" rpy="0 -1.5708 0"></origin>
<parent link="l_shin"></parent>
<child link="l_foot"></child>
<axis xyz="1 0 0"></axis>
<limit effort="3.1" lower="-0.785398163397" upper="0.785398163397" velocity="7.0"></limit>
</joint>
<joint name="abs_y" type="revolute">
<origin xyz="0 -0.017 0.061" rpy="1.5707963267949 0 0"></origin>
<parent link="pelvis"></parent>
<child link="abs_motors"></child>
<axis xyz="-1 0 0"></axis>
<limit effort="7.3" lower="-0.872664625997" upper="0.209439510239" velocity="8.2"></limit>
</joint>
<joint name="abs_x" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<parent link="abs_motors"></parent>
<child link="abdomen"></child>
<axis xyz="0 0 1"></axis>
<limit effort="7.3" lower="-0.785398163397" upper="0.785398163397" velocity="8.2"></limit>
</joint>
<joint name="abs_z" type="revolute">
<origin xyz="0 0.0516374742048976 0" rpy="0 0 0"></origin>
<parent link="abdomen"></parent>
<child link="spine"></child>
<axis xyz="0 1 0"></axis>
<limit effort="3.1" lower="-1.57079632679" upper="1.57079632679" velocity="7.0"></limit>
</joint>
<joint name="bust_y" type="revolute">
<origin xyz="0 0.07985 0.00279999999999998" rpy="0 0 0"></origin>
<parent link="spine"></parent>
<child link="bust_motors"></child>
<axis xyz="-1 0 0"></axis>
<limit effort="3.1" lower="-1.16937059884" upper="0.471238898038" velocity="7.0"></limit>
</joint>
<joint name="bust_x" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"></origin>
<parent link="bust_motors"></parent>
<child link="chest"></child>
<axis xyz="0 0 1"></axis>
<limit effort="3.1" lower="-0.698131700798" upper="0.698131700798" velocity="7.0"></limit>
</joint>
<joint name="head_z" type="revolute">
<origin xyz="0 0.084 0.00499999999999996" rpy="0 0 0"></origin>
<parent link="chest"></parent>
<child link="neck"></child>
<axis xyz="0 1 0"></axis>
<limit effort="1.8" lower="-1.57079632679" upper="1.57079632679" velocity="10.0"></limit>
</joint>
<joint name="head_y" type="revolute">
<origin xyz="0 0.0199999999999999 0" rpy="-0.349065850398866 0 0"></origin>
<parent link="neck"></parent>
<child link="head"></child>
<axis xyz="-1 0 0"></axis>
<limit effort="1.8" lower="-0.785398163397" upper="0.10471975512" velocity="10.0"></limit>
</joint>
<joint name="l_shoulder_y" type="revolute">
<origin xyz="0.0771000000000001 0.0499999999999999 0.00399999999999997" rpy="-1.5707963267949 0 0"></origin>
<parent link="chest"></parent>
<child link="l_shoulder"></child>
<axis xyz="1 0 0"></axis>
<limit effort="3.1" lower="-2.09439510239" upper="2.70526034059" velocity="7.0"></limit>
</joint>
<joint name="l_shoulder_x" type="revolute">
<origin xyz="0.0284 0 0" rpy="3.14159265358979 0 1.5707963267949"></origin>
<parent link="l_shoulder"></parent>
<child link="l_shoulder_motor"></child>
<axis xyz="0 0 1"></axis>
<limit effort="3.1" lower="-1.83259571459" upper="1.91986217719" velocity="7.0"></limit>
</joint>
<joint name="l_arm_z" type="revolute">
<origin xyz="0 0.03625 0.0185000000000001" rpy="0 0 0"></origin>
<parent link="l_shoulder_motor"></parent>
<child link="l_upper_arm"></child>
<axis xyz="0 1 0"></axis>
<limit effort="3.1" lower="-1.83259571459" upper="1.83259571459" velocity="7.0"></limit>
</joint>
<joint name="l_elbow_y" type="revolute">
<origin xyz="0 0.11175 -0.00999999999999998" rpy="0 0 0"></origin>
<parent link="l_upper_arm"></parent>
<child link="l_forearm"></child>
<axis xyz="1 0 0"></axis>
<limit effort="3.1" lower="-2.58308729295" upper="0.0174532925199" velocity="7.0"></limit>
</joint>
<joint name="r_shoulder_y" type="revolute">
<origin xyz="-0.0770999999999999 0.0500000000000002 0.00400000000000003" rpy="-1.5707963267949 0 0"></origin>
<parent link="chest"></parent>
<child link="r_shoulder"></child>
<axis xyz="-1 0 0"></axis>
<limit effort="3.1" lower="-2.70526034059" upper="2.09439510239" velocity="7.0"></limit>
</joint>
<joint name="r_shoulder_x" type="revolute">
<origin xyz="-0.0284 0 0" rpy="3.14159265358979 0 -1.5707963267949"></origin>
<parent link="r_shoulder"></parent>
<child link="r_shoulder_motor"></child>
<axis xyz="0 0 -1"></axis>
<limit effort="3.1" lower="-1.91986217719" upper="1.83259571459" velocity="7.0"></limit>
</joint>
<joint name="r_arm_z" type="revolute">
<origin xyz="0 0.03625 0.0185000000000002" rpy="0 0 0"></origin>
<parent link="r_shoulder_motor"></parent>
<child link="r_upper_arm"></child>
<axis xyz="0 1 0"></axis>
<limit effort="3.1" lower="-1.83259571459" upper="1.83259571459" velocity="7.0"></limit>
</joint>
<joint name="r_elbow_y" type="revolute">
<origin xyz="0 0.11175 -0.01" rpy="0 0 0"></origin>
<parent link="r_upper_arm"></parent>
<child link="r_forearm"></child>
<axis xyz="-1 0 0"></axis>
<limit effort="3.1" lower="-0.0174532925199" upper="2.58308729295" velocity="7.0"></limit>
</joint>
</robot>