跳到主要内容
版本:外骨骼手套

硬件规格

外骨骼手套 V2

型号:TeleGlove-Skel-V2

属性参数
尺寸20×15×10cm
重量195±5g
关节数量21
穿戴时间5秒即可上手
反馈形式5手指10级震动反馈
手套尺寸S/M
连接方式有线直连/连接无线模块
工作电压5V
工作时长2.5-3H(与无线模块共用)
环境工作温度:0 °C ~ 40 °C;储存温度:-20 °C ~ 60 °C;湿度:10%~90%无冷凝;储存湿度:5%~95%无冷凝
数据输出编码器/加速度计/陀螺仪
数据传输频率120Hz
磁编码器精度1.0±0.2度
加速度测量范围± 16 g
陀螺仪测量范围± 2000 deg/s

配件

无线(Wi-Fi)模块

型号:TS-WM-WF

无线模块正面

无线模块背面

手背定位结构(pico)

型号:TS-PA-PICO

手背定位结构

手指控制单元

型号:TS-FCM-L/TS-FCM-R

手指控制单元特写

手指控制单元佩戴效果


数据接口

输入

/io_esk/vibration_feedback

  • Topic/io_esk/vibration_feedback
  • Typestd_msgs/Float64MultiArray
  • 响应频率:120Hz
  • 用途:用于外骨骼指尖振动反馈
  • 内容解释
// Float64MultiArray
// ros 官方msg
std_msgs/MultiArrayLayout layout
float64[] data
// 震动等级: 1-10级别,0为不震动
// 接收力反馈数据序号: 顺序: 0-4 右手,5-9 左手。
// 右手从thumb->pinky->ring->middle->index
// 左手从thumb->index->middle->ring->pinky

输出

/io_esk/joint_data

  • Topic/io_esk/joint_data
  • Typesensor_msgs/JointState.msg
  • 输出频率:120Hz
  • 用途:输出外骨骼手套关节编码器数据

/io_esk/joystick_data

  • Topic/io_esk/joystick_data
  • Typesensor_msgs/Joy.msg
  • 输出频率:120Hz
  • 用途:输出外骨骼手指控制单元摇杆数据
  • 内容解释
std_msgs/Header header
float32[2] axes #右
float32[2] axes #左
int32[4] buttons#右
int32[4] buttons#左

/io_esk/tf

  • Topic/io_esk/tf
  • Typetf2_msgs/TFMessage.msg
  • 输出频率:120Hz
  • 用途:输出外骨骼手套所有连杆数据
  • 内容解释:外骨骼所有link的位置与姿态信息
//TFMessage.msg
geometry_msgs/TransformStamped[] transforms

发布tf为如下link相对于base_link的坐标变化:

tips(指尖)

right_hand
right_thumb_tip
right_index_tip
right_middle_tip
right_ring_tip
right_pinky_tip
left_hand
left_thumb_tip
left_index_tip
left_middle_tip
left_ring_tip
left_pinky_tip

exoskeleton(外骨骼连杆)

link_RightSkeletonBase
link_RightSkeletonThumbBase
link_RightSkeletonThumb1
link_RightSkeletonThumb2
link_RightSkeletonThumb3
link_RightSkeletonThumb4
link_RightSkeletonIndex1
link_RightSkeletonIndex2
link_RightSkeletonIndex3
link_RightSkeletonIndex4
link_RightSkeletonMiddle1
link_RightSkeletonMiddle2
link_RightSkeletonMiddle3
link_RightSkeletonMiddle4
link_RightSkeletonRing1
link_RightSkeletonRing2
link_RightSkeletonRing3
link_RightSkeletonRing4
link_RightSkeletonPinky1
link_RightSkeletonPinky2
link_RightSkeletonPinky3
link_RightSkeletonPinky4
link_LeftSkeletonBase
link_LeftSkeletonThumbBase
link_LeftSkeletonThumb1
link_LeftSkeletonThumb2
link_LeftSkeletonThumb3
link_LeftSkeletonThumb4
link_LeftSkeletonIndex1
link_LeftSkeletonIndex2
link_LeftSkeletonIndex3
link_LeftSkeletonIndex4
link_LeftSkeletonMiddle1
link_LeftSkeletonMiddle2
link_LeftSkeletonMiddle3
link_LeftSkeletonMiddle4
link_LeftSkeletonRing1
link_LeftSkeletonRing2
link_LeftSkeletonRing3
link_LeftSkeletonRing4
link_LeftSkeletonPinky1
link_LeftSkeletonPinky2
link_LeftSkeletonPinky3
link_LeftSkeletonPinky4

参考 URDF

tf 对应的 URDF 如下(blender_human_skeleton_v4.urdf):

<?xml version='1.0' encoding='utf-8'?>
<robot name="skeleton_hands">

<link name="base_link" />


<link name="link_RightSkeletonBase">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_base_link.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_base_link.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00796015810167955 -0.0223806324874924 -0.00754865265348615" rpy="0 0 0" />
<mass value="0.0381015295019329" />
<inertia ixx="1.57718800745917E-05" ixy="6.20482209711992E-07" ixz="-6.07587294987589E-07" iyy="2.35787256108512E-05" iyz="-3.31320823452304E-07" izz="3.85148762850539E-05" />
</inertial>
</link>
<link name="link_RightSkeletonThumbBase">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1base.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1base.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00565122071301274 -0.000501255972792568 0.0144743281019806" rpy="0 0 0" />
<mass value="0.00503517876942867" />
<inertia ixx="3.0284978913365E-07" ixy="-4.84190552283924E-09" ixz="4.64240301448541E-08" iyy="4.03125978353386E-07" iyz="1.09069756102581E-08" izz="1.64098939217181E-07" />
</inertial>
</link>
<link name="link_RightSkeletonThumb1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307505347316 0.00184077480530574 0.00372077729598377" rpy="0 0 0" />
<mass value="0.00142104750359472" />
<inertia ixx="7.34398085023081E-08" ixy="-2.41328511399796E-09" ixz="-3.3240568542648E-09" iyy="4.17889579868087E-08" iyz="-1.49123152617831E-08" izz="4.72743798877277E-08" />
</inertial>
</link>
<link name="link_RightSkeletonThumb2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_2.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00232322870955951 0.0181721928412631 0.0329507487373648" rpy="0 0 0" />
<mass value="0.00619479805127885" />
<inertia ixx="3.99788034904245E-06" ixy="-5.39381049868907E-09" ixz="3.61902852797014E-09" iyy="2.30653492100461E-06" iyz="-1.85763694879346E-06" izz="1.73763444181624E-06" />
</inertial>
</link>
<link name="link_RightSkeletonThumb3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00212757980775651 0.00134841278506191 0.019940757393612" rpy="0 0 0" />
<mass value="0.00375708793059457" />
<inertia ixx="7.71326509106515E-07" ixy="-1.5101709953254E-09" ixz="6.67792513897098E-09" iyy="7.24505391043061E-07" iyz="-1.00538276089503E-07" izz="7.39249486010084E-08" />
</inertial>
</link>
<link name="link_RightSkeletonThumb4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_4.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer1_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269144829495772 0.00131123432438183 -0.0106491104624541" rpy="0 0 0" />
<mass value="0.00283813885886545" />
<inertia ixx="2.95191006974025E-07" ixy="1.71597808354591E-09" ixz="-1.5368571085107E-08" iyy="2.53523111794926E-07" iyz="4.47728143031876E-09" izz="9.65716906164859E-08" />
</inertial>
</link>
<link name="link_RightSkeletonIndex1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307504266343 0.00184077481598622 0.00372077728256266" rpy="0 0 0" />
<mass value="0.00142104749535094" />
<inertia ixx="7.34398089807809E-08" ixy="-2.41328507686512E-09" ixz="-3.32405672713572E-09" iyy="4.1788957914828E-08" iyz="-1.49123154155797E-08" izz="4.72743801943149E-08" />
</inertial>
</link>
<link name="link_RightSkeletonIndex2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_2.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225494995541581 0.0152388468351605 0.0296839473890663" rpy="0 0 0" />
<mass value="0.00558495756330841" />
<inertia ixx="2.91836620840625E-06" ixy="-4.14851984558481E-09" ixz="4.21806668429099E-09" iyy="1.74531636320502E-06" iyz="-1.32500629306026E-06" izz="1.21440970517614E-06" />
</inertial>
</link>
<link name="link_RightSkeletonIndex3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235572032002532 0.021473120708047 0.0285487191425626" rpy="0 0 0" />
<mass value="0.00663685611795157" />
<inertia ixx="4.2149172670233E-06" ixy="-3.2931532345881E-09" ixz="1.81725175793322E-08" iyy="1.11332596242003E-06" iyz="-1.23177219223019E-06" izz="3.14896536873041E-06" />
</inertial>
</link>
<link name="link_RightSkeletonIndex4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_4.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer2_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.0026914180675609 0.00131123336884371 -0.0106491162895952" rpy="0 0 0" />
<mass value="0.00283814206573991" />
<inertia ixx="2.95191305819849E-07" ixy="1.71594002207152E-09" ixz="-1.53679050089507E-08" iyy="2.535226738251E-07" iyz="4.47721015720482E-09" izz="9.6571438657795E-08" />
</inertial>
</link>
<link name="link_RightSkeletonMiddle1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307508570481 0.00184077478338782 0.0037207773602195" rpy="0 0 0" />
<mass value="0.00142104751859945" />
<inertia ixx="7.3439809623175E-08" ixy="-2.41328476584004E-09" ixz="-3.32405702526707E-09" iyy="4.17889587410191E-08" iyz="-1.49123151802322E-08" izz="4.72743806400365E-08" />
</inertial>
</link>
<link name="link_RightSkeletonMiddle2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_2.STL" />
</geometry>
<material name="">
<color rgba="0.615686274509804 0.643137254901961 0.674509803921569 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225495233843075 0.0152388460708894 0.029683944118068" rpy="0 0 0" />
<mass value="0.00558495686016827" />
<inertia ixx="2.91836682320128E-06" ixy="-4.14856599032089E-09" ixz="4.21793857169474E-09" iyy="1.74531712287045E-06" iyz="-1.32500694741923E-06" izz="1.21440950221904E-06" />
</inertial>
</link>
<link name="link_RightSkeletonMiddle3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235572479349241 0.0214731366915545 0.0285487400327757" rpy="0 0 0" />
<mass value="0.00663684957658263" />
<inertia ixx="4.21491005720671E-06" ixy="-3.29390834910374E-09" ixz="1.8171772300357E-08" iyy="1.11332106780687E-06" iyz="-1.2317692593153E-06" izz="3.14896228623323E-06" />
</inertial>
</link>
<link name="link_RightSkeletonMiddle4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_4.STL" />
</geometry>
<material name="">
<color rgba="0.615686274509804 0.643137254901961 0.674509803921569 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer3_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269142354774019 -0.000938576252218395 -0.0139532868338926" rpy="0 0 0" />
<mass value="0.00283813730192772" />
<inertia ixx="2.95191343112668E-07" ixy="1.71603422344851E-09" ixz="-1.53680591698325E-08" iyy="2.53522363104874E-07" iyz="4.47723638318037E-09" izz="9.65713727636697E-08" />
</inertial>
</link>
<link name="link_RightSkeletonRing1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307508570481 0.00184077478338781 0.0037207773602195" rpy="0 0 0" />
<mass value="0.00142104751859945" />
<inertia ixx="7.34398096231749E-08" ixy="-2.41328476584003E-09" ixz="-3.32405702526709E-09" iyy="4.1788958741019E-08" iyz="-1.49123151802322E-08" izz="4.72743806400364E-08" />
</inertial>
</link>
<link name="link_RightSkeletonRing2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_2.STL" />
</geometry>
<material name="">
<color rgba="0.615686274509804 0.643137254901961 0.674509803921569 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225495233843075 0.0152388460708892 0.029683944118067" rpy="0 0 0" />
<mass value="0.00558495686016845" />
<inertia ixx="2.9183668263298E-06" ixy="-4.14856589933394E-09" ixz="4.21793867181136E-09" iyy="1.7453171255457E-06" iyz="-1.32500694813122E-06" izz="1.21440950270268E-06" />
</inertial>
</link>
<link name="link_RightSkeletonRing3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235572454769539 0.0214731363844119 0.0285487393993492" rpy="0 0 0" />
<mass value="0.00663684971073181" />
<inertia ixx="4.21491023862972E-06" ixy="-3.29387584199395E-09" ixz="1.81718097893476E-08" iyy="1.11332120740036E-06" iyz="-1.23176935213484E-06" izz="3.14896233832563E-06" />
</inertial>
</link>
<link name="link_RightSkeletonRing4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_4.STL" />
</geometry>
<material name="">
<color rgba="0.615686274509804 0.643137254901961 0.674509803921569 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer4_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269142354774019 -0.000938576252218465 -0.0139532868338925" rpy="0 0 0" />
<mass value="0.00283813730192769" />
<inertia ixx="2.95191343112664E-07" ixy="1.71603422344794E-09" ixz="-1.53680591698328E-08" iyy="2.53522363104871E-07" iyz="4.47723638318119E-09" izz="9.65713727636688E-08" />
</inertial>
</link>
<link name="link_RightSkeletonPinky1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307510727016 0.0018407747681536 0.00372077739461437" rpy="0 0 0" />
<mass value="0.00142104752949724" />
<inertia ixx="7.34398098284156E-08" ixy="-2.41328463578981E-09" ixz="-3.32405717829616E-09" iyy="4.1788959109633E-08" iyz="-1.49123150597226E-08" izz="4.72743807982806E-08" />
</inertial>
</link>
<link name="link_RightSkeletonPinky2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_2.STL" />
</geometry>
<material name="">
<color rgba="0.615686274509804 0.643137254901961 0.674509803921569 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225495398472628 0.0152388453344131 0.0296839389686488" rpy="0 0 0" />
<mass value="0.0055849572264132" />
<inertia ixx="2.9183676470236E-06" ixy="-4.14858966781097E-09" ixz="4.21787871476057E-09" iyy="1.74531806183641E-06" iyz="-1.32500756906238E-06" izz="1.21440933015917E-06" />
</inertial>
</link>
<link name="link_RightSkeletonPinky3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235572771755228 0.0214731406786556 0.0285487426831204" rpy="0 0 0" />
<mass value="0.00663684736422184" />
<inertia ixx="4.2149092003135E-06" ixy="-3.29427631293345E-09" ixz="1.8171488817969E-08" iyy="1.11332047704093E-06" iyz="-1.23176906960859E-06" izz="3.14896143733786E-06" />
</inertial>
</link>
<link name="link_RightSkeletonPinky4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_4.STL" />
</geometry>
<material name="">
<color rgba="0.615686274509804 0.643137254901961 0.674509803921569 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/R_figer5_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269142161091054 0.00131124045330436 -0.0106491028537343" rpy="0 0 0" />
<mass value="0.0028381369220279" />
<inertia ixx="2.95191404600699E-07" ixy="1.71593490047463E-09" ixz="-1.53680891113599E-08" iyy="2.53522400439724E-07" iyz="4.47736013107046E-09" izz="9.65714677930946E-08" />
</inertial>
</link>


<link name="link_LeftSkeletonBase">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_base_link.STL" />
</geometry>
<material name="">
<color rgba="0.615686274509804 0.643137254901961 0.674509803921569 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_base_link.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00795971826189585 -0.0223786822134 -0.00754886924823978" rpy="0 0 0" />
<mass value="0.0381033782864806" />
<inertia ixx="1.57715027656341E-05" ixy="-6.20672688310259E-07" ixz="6.07301367718693E-07" iyy="2.35777844365302E-05" iyz="-3.31185265424762E-07" izz="3.85136702094599E-05" />
</inertial>
</link>
<link name="link_LeftSkeletonThumbBase">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1base.STL" />
</geometry>
<material name="">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1base.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00565122125132897 -0.000501255807949387 -0.0144743297760789" rpy="0 0 0" />
<mass value="0.00503517796554752" />
<inertia ixx="3.02849721330865E-07" ixy="-4.84190547312495E-09" ixz="-4.64239909926053E-08" iyy="4.03125891253508E-07" iyz="-1.09069982752038E-08" izz="1.64098935188539E-07" />
</inertial>
</link>
<link name="link_LeftSkeletonThumb1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307505347319 0.00184077480530568 0.00372077729598363" rpy="0 0 0" />
<mass value="0.00142104750359472" />
<inertia ixx="7.34398085023082E-08" ixy="-2.41328511399795E-09" ixz="-3.32405685426481E-09" iyy="4.17889579868088E-08" iyz="-1.49123152617831E-08" izz="4.72743798877278E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonThumb2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_2.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00232322870955949 0.0181721928412632 0.0329507487373656" rpy="0 0 0" />
<mass value="0.00619479805127877" />
<inertia ixx="3.99788034854978E-06" ixy="-5.39381049615914E-09" ixz="3.61902852100043E-09" iyy="2.30653492179191E-06" iyz="-1.85763694836304E-06" izz="1.73763444053624E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonThumb3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00212757993564025 0.00134841281276385 0.0199407577558663" rpy="0 0 0" />
<mass value="0.00375708785451946" />
<inertia ixx="7.71326480727341E-07" ixy="-1.51017237583647E-09" ixz="6.67791712324156E-09" iyy="7.24505359944446E-07" iyz="-1.00538270710119E-07" izz="7.39249458745912E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonThumb4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_4.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer1_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269144829495786 0.00131123432438181 -0.0106491104624541" rpy="0 0 0" />
<mass value="0.00283813885886545" />
<inertia ixx="2.95191006974024E-07" ixy="1.715978083546E-09" ixz="-1.53685710851065E-08" iyy="2.53523111794926E-07" iyz="4.47728143031873E-09" izz="9.65716906164854E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonIndex1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307509026819 0.00184077478079219 0.00372077737035408" rpy="0 0 0" />
<mass value="0.00142104752116292" />
<inertia ixx="7.34398097705605E-08" ixy="-2.41328471829701E-09" ixz="-3.32405704960183E-09" iyy="4.17889588569522E-08" iyz="-1.49123151713754E-08" izz="4.7274380734949E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonIndex2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_2.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225495196610019 0.0152388465015396 0.0296839471721429" rpy="0 0 0" />
<mass value="0.00558495597861908" />
<inertia ixx="2.91836638778982E-06" ixy="-4.14856306465521E-09" ixz="4.21794456616969E-09" iyy="1.74531664665666E-06" iyz="-1.32500667567509E-06" izz="1.21440955407491E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonIndex3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235571534919174 0.0214730659761306 0.0285487030071992" rpy="0 0 0" />
<mass value="0.00663689292635733" />
<inertia ixx="4.21492012071515E-06" ixy="-3.29363285361801E-09" ixz="1.81727320848805E-08" iyy="1.11332144347172E-06" iyz="-1.23177645824186E-06" izz="3.14896956323261E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonIndex4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_4.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer2_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269142139243032 0.00131119366606559 -0.0106491009653354" rpy="0 0 0" />
<mass value="0.00283813624759799" />
<inertia ixx="2.951912997642E-07" ixy="1.71678009357066E-09" ixz="-1.5368007180772E-08" iyy="2.53522873664869E-07" iyz="4.47648334924128E-09" izz="9.65716410018517E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonMiddle1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307506943234 0.00184077479664554 0.00372077733726794" rpy="0 0 0" />
<mass value="0.00142104751099454" />
<inertia ixx="7.34398095058843E-08" ixy="-2.413284858295E-09" ixz="-3.3240569053412E-09" iyy="4.17889585025189E-08" iyz="-1.49123152884824E-08" izz="4.7274380532837E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonMiddle2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_2.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225495044703111 0.015238847203026 0.0296839510031334" rpy="0 0 0" />
<mass value="0.00558495571115789" />
<inertia ixx="2.91836576376808E-06" ixy="-4.14853801417219E-09" ixz="4.21801887014206E-09" iyy="1.74531591715227E-06" iyz="-1.32500615370565E-06" izz="1.21440969393698E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonMiddle3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235575036042073 0.0214732052026604 0.0285488068489457" rpy="0 0 0" />
<mass value="0.00663681790738949" />
<inertia ixx="4.21488667292334E-06" ixy="-3.29755585159406E-09" ixz="1.8169244364376E-08" iyy="1.11330618522731E-06" iyz="-1.23176105112002E-06" izz="3.14894885124307E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonMiddle4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_4.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer3_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269143985186518 0.00131123900117359 -0.0106491096397188" rpy="0 0 0" />
<mass value="0.00283814024815753" />
<inertia ixx="2.95191093276479E-07" ixy="1.71570093387614E-09" ixz="-1.53684896368711E-08" iyy="2.53523011704854E-07" iyz="4.47743478896999E-09" izz="9.65718896046615E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonRing1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307506943234 0.00184077479664554 0.00372077733726793" rpy="0 0 0" />
<mass value="0.00142104751099453" />
<inertia ixx="7.34398095058843E-08" ixy="-2.413284858295E-09" ixz="-3.32405690534121E-09" iyy="4.17889585025189E-08" iyz="-1.49123152884824E-08" izz="4.7274380532837E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonRing2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_2.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225495044703106 0.0152388472030259 0.029683951003133" rpy="0 0 0" />
<mass value="0.00558495571115816" />
<inertia ixx="2.91836576375482E-06" ixy="-4.14853811090769E-09" ixz="4.21801880889743E-09" iyy="1.74531591777441E-06" iyz="-1.32500615504142E-06" izz="1.21440969333159E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonRing3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235575036042072 0.0214732052026591 0.0285488068489463" rpy="0 0 0" />
<mass value="0.00663681790738944" />
<inertia ixx="4.21488666888122E-06" ixy="-3.29755568884729E-09" ixz="1.81692444753661E-08" iyy="1.11330618321482E-06" iyz="-1.23176105206024E-06" izz="3.14894884915112E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonRing4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_4.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer4_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269143985186522 0.00131123900117358 -0.010649109639719" rpy="0 0 0" />
<mass value="0.00283814024815758" />
<inertia ixx="2.95191093276484E-07" ixy="1.71570093387564E-09" ixz="-1.53684896368724E-08" iyy="2.53523011704858E-07" iyz="4.4774347889687E-09" izz="9.65718896046638E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonPinky1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_1.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_1.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="0.00103307504563986 0.00184077481534127 0.00372077729595737" rpy="0 0 0" />
<mass value="0.00142104749852734" />
<inertia ixx="7.34398091643881E-08" ixy="-2.41328502755941E-09" ixz="-3.32405673881618E-09" iyy="4.17889580664544E-08" iyz="-1.49123154253083E-08" izz="4.72743802888997E-08" />
</inertial>
</link>
<link name="link_LeftSkeletonPinky2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_2.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_2.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00225495048675595 0.0152388470456515 0.0296839486862967" rpy="0 0 0" />
<mass value="0.00558495640568594" />
<inertia ixx="2.91836608158061E-06" ixy="-4.14853379397085E-09" ixz="4.21802965573986E-09" iyy="1.74531625324304E-06" iyz="-1.32500629125066E-06" izz="1.21440967547373E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonPinky3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_3.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_3.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00235576376837485 0.0214732139844029 0.0285488335633921" rpy="0 0 0" />
<mass value="0.00663681351825927" />
<inertia ixx="4.21487885442923E-06" ixy="-3.29902839678352E-09" ixz="1.8166501453508E-08" iyy="1.11329897328873E-06" iyz="-1.23175774928956E-06" izz="3.14894672413315E-06" />
</inertial>
</link>
<link name="link_LeftSkeletonPinky4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_4.STL" />
</geometry>
<material name="">
<color rgba="0.866666666666667 0.866666666666667 0.890196078431372 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://io_mocap/description/meshes/L_figer5_4.STL" />
</geometry>
</collision>
<inertial>
<origin xyz="-0.00269142147355608 0.00131124179778838 -0.0106491029625067" rpy="0 0 0" />
<mass value="0.00283813750198794" />
<inertia ixx="2.9519141935042E-07" ixy="1.71585604436604E-09" ixz="-1.53681173379396E-08" iyy="2.5352240055643E-07" iyz="4.47741719154892E-09" izz="9.65715578191067E-08" />
</inertial>
</link>


<link name="right_thumb_tip" />
<link name="right_index_tip" />
<link name="right_middle_tip" />
<link name="right_ring_tip" />
<link name="right_pinky_tip" />
<link name="left_thumb_tip" />
<link name="left_index_tip" />
<link name="left_middle_tip" />
<link name="left_ring_tip" />
<link name="left_pinky_tip" />
<link name="right_hand" />
<link name="left_hand" />


<joint name="joint_RightSkeletonBase" type="fixed">
<parent link="base_link" />
<child link="link_RightSkeletonBase" />
<origin xyz="0.05 0 0" rpy="0 0 0" />
</joint>

<joint name="joint_LeftSkeletonBase" type="fixed">
<parent link="base_link" />
<child link="link_LeftSkeletonBase" />
<origin xyz="-0.05 0 0" rpy="0 0 0" />
</joint>


<joint name="joint_RightSkeletonThumbBase" type="revolute">
<origin xyz="-0.040042 -0.053331 -0.015" rpy="3.1416 0 2.1472" />
<parent link="link_RightSkeletonBase" />
<child link="link_RightSkeletonThumbBase" />
<axis xyz="1 0 0" />
<limit lower="-3.14" upper="3.14" effort="100" velocity="1" />
</joint>
<joint name="joint_RightSkeletonThumb1" type="revolute">
<origin xyz="-0.0072 -0.006 0.0195" rpy="1.5708 1.5708 0" />
<parent link="link_RightSkeletonThumbBase" />
<child link="link_RightSkeletonThumb1" />
<axis xyz="0 0 1" />
<limit lower="-3.14" upper="3.14" effort="100" velocity="1" />
</joint>
<joint name="joint_RightSkeletonThumb2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-1.309 0 0" />
<parent link="link_RightSkeletonThumb1" />
<child link="link_RightSkeletonThumb2" />
<axis xyz="1 0 0" />
<limit lower="-3.14" upper="3.14" effort="100" velocity="1" />
</joint>
<joint name="joint_RightSkeletonThumb3" type="revolute">
<origin xyz="0 0.050552 0.068334" rpy="-0.81433 0 0" />
<parent link="link_RightSkeletonThumb2" />
<child link="link_RightSkeletonThumb3" />
<axis xyz="1 0 0" />
<limit lower="-3.14" upper="3.14" effort="100" velocity="1" />
</joint>
<joint name="joint_RightSkeletonThumb4" type="revolute">
<origin xyz="0 0.0080746 0.045794" rpy="2.5307 0 0" />
<parent link="link_RightSkeletonThumb3" />
<child link="link_RightSkeletonThumb4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonIndex1" type="revolute">
<origin xyz="-0.021871 0.0026351 -0.0024377" rpy="0 -0.2618 -0.1199" />
<parent link="link_RightSkeletonBase" />
<child link="link_RightSkeletonIndex1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonIndex2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_RightSkeletonIndex1" />
<child link="link_RightSkeletonIndex2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonIndex3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_RightSkeletonIndex2" />
<child link="link_RightSkeletonIndex3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonIndex4" type="revolute">
<origin xyz="0 0.064952 0.0375" rpy="1.2217 0 0" />
<parent link="link_RightSkeletonIndex3" />
<child link="link_RightSkeletonIndex4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonMiddle1" type="revolute">
<origin xyz="0 0 0.0005" rpy="0 0 -0.1199" />
<parent link="link_RightSkeletonBase" />
<child link="link_RightSkeletonMiddle1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonMiddle2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_RightSkeletonMiddle1" />
<child link="link_RightSkeletonMiddle2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonMiddle3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_RightSkeletonMiddle2" />
<child link="link_RightSkeletonMiddle3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonMiddle4" type="revolute">
<origin xyz="0 0.062616 0.040744" rpy="1.2217 0 0" />
<parent link="link_RightSkeletonMiddle3" />
<child link="link_RightSkeletonMiddle4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonRing1" type="revolute">
<origin xyz="0.020849 -0.002512 0.0005" rpy="0 0 -0.1199" />
<parent link="link_RightSkeletonBase" />
<child link="link_RightSkeletonRing1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonRing2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_RightSkeletonRing1" />
<child link="link_RightSkeletonRing2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonRing3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_RightSkeletonRing2" />
<child link="link_RightSkeletonRing3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonRing4" type="revolute">
<origin xyz="0 0.062616 0.040744" rpy="1.2217 0 0" />
<parent link="link_RightSkeletonRing3" />
<child link="link_RightSkeletonRing4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonPinky1" type="revolute">
<origin xyz="0.042036 -0.0050645 -0.0016681" rpy="0 0.17453 -0.1199" />
<parent link="link_RightSkeletonBase" />
<child link="link_RightSkeletonPinky1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonPinky2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_RightSkeletonPinky1" />
<child link="link_RightSkeletonPinky2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonPinky3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_RightSkeletonPinky2" />
<child link="link_RightSkeletonPinky3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_RightSkeletonPinky4" type="revolute">
<origin xyz="0 0.064952 0.0375" rpy="1.2217 0 0" />
<parent link="link_RightSkeletonPinky3" />
<child link="link_RightSkeletonPinky4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>


<joint name="joint_LeftSkeletonThumbBase" type="revolute">
<origin xyz="0.040042 -0.053331 -0.015" rpy="0 0 0.99442" />
<parent link="link_LeftSkeletonBase" />
<child link="link_LeftSkeletonThumbBase" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonThumb1" type="revolute">
<origin xyz="-0.0072 -0.006 -0.0195" rpy="1.5708 1.5708 0" />
<parent link="link_LeftSkeletonThumbBase" />
<child link="link_LeftSkeletonThumb1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonThumb2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-1.309 0 0" />
<parent link="link_LeftSkeletonThumb1" />
<child link="link_LeftSkeletonThumb2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonThumb3" type="revolute">
<origin xyz="0 0.050552 0.068334" rpy="-0.81433 0 0" />
<parent link="link_LeftSkeletonThumb2" />
<child link="link_LeftSkeletonThumb3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonThumb4" type="revolute">
<origin xyz="0 0.0080746 0.045794" rpy="2.5307 0 0" />
<parent link="link_LeftSkeletonThumb3" />
<child link="link_LeftSkeletonThumb4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonIndex1" type="revolute">
<origin xyz="0.021871 0.0026351 -0.0024377" rpy="0 0.2618 0.1199" />
<parent link="link_LeftSkeletonBase" />
<child link="link_LeftSkeletonIndex1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonIndex2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_LeftSkeletonIndex1" />
<child link="link_LeftSkeletonIndex2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonIndex3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_LeftSkeletonIndex2" />
<child link="link_LeftSkeletonIndex3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonIndex4" type="revolute">
<origin xyz="0 0.064952 0.0375" rpy="1.2217 0 0" />
<parent link="link_LeftSkeletonIndex3" />
<child link="link_LeftSkeletonIndex4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonMiddle1" type="revolute">
<origin xyz="0 0 0.0005" rpy="0 0 0.1199" />
<parent link="link_LeftSkeletonBase" />
<child link="link_LeftSkeletonMiddle1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonMiddle2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_LeftSkeletonMiddle1" />
<child link="link_LeftSkeletonMiddle2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonMiddle3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_LeftSkeletonMiddle2" />
<child link="link_LeftSkeletonMiddle3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonMiddle4" type="revolute">
<origin xyz="0 0.064952 0.0375" rpy="1.2217 0 0" />
<parent link="link_LeftSkeletonMiddle3" />
<child link="link_LeftSkeletonMiddle4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonRing1" type="revolute">
<origin xyz="-0.020849 -0.002512 0.0005" rpy="0 0 0.1199" />
<parent link="link_LeftSkeletonBase" />
<child link="link_LeftSkeletonRing1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonRing2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_LeftSkeletonRing1" />
<child link="link_LeftSkeletonRing2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonRing3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_LeftSkeletonRing2" />
<child link="link_LeftSkeletonRing3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonRing4" type="revolute">
<origin xyz="0 0.064952 0.0375" rpy="1.2217 0 0" />
<parent link="link_LeftSkeletonRing3" />
<child link="link_LeftSkeletonRing4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonPinky1" type="revolute">
<origin xyz="-0.042036 -0.0050645 -0.0016681" rpy="0 -0.17453 0.1199" />
<parent link="link_LeftSkeletonBase" />
<child link="link_LeftSkeletonPinky1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonPinky2" type="revolute">
<origin xyz="0.0036 0.0074761 0.0074414" rpy="-0.75647 0 0" />
<parent link="link_LeftSkeletonPinky1" />
<child link="link_LeftSkeletonPinky2" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonPinky3" type="revolute">
<origin xyz="0 0.043889 0.062046" rpy="0.46849 0 0" />
<parent link="link_LeftSkeletonPinky2" />
<child link="link_LeftSkeletonPinky3" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>
<joint name="joint_LeftSkeletonPinky4" type="revolute">
<origin xyz="0 0.064952 0.0375" rpy="1.2217 0 0" />
<parent link="link_LeftSkeletonPinky3" />
<child link="link_LeftSkeletonPinky4" />
<axis xyz="1 0 0" />
<limit lower="0" upper="0" effort="0" velocity="0" />
</joint>


<joint name="right_thumb_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_RightSkeletonThumb4" />
<child link="right_thumb_tip" />
</joint>
<joint name="right_index_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_RightSkeletonIndex4" />
<child link="right_index_tip" />
</joint>
<joint name="right_middle_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_RightSkeletonMiddle4" />
<child link="right_middle_tip" />
</joint>
<joint name="right_ring_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_RightSkeletonRing4" />
<child link="right_ring_tip" />
</joint>
<joint name="right_pinky_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_RightSkeletonPinky4" />
<child link="right_pinky_tip" />
</joint>
<joint name="left_thumb_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_LeftSkeletonThumb4" />
<child link="left_thumb_tip" />
</joint>
<joint name="left_index_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_LeftSkeletonIndex4" />
<child link="left_index_tip" />
</joint>
<joint name="left_middle_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_LeftSkeletonMiddle4" />
<child link="left_middle_tip" />
</joint>
<joint name="left_ring_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_LeftSkeletonRing4" />
<child link="left_ring_tip" />
</joint>
<joint name="left_pinky_tip_joint" type="fixed">
<origin xyz="-0.0026 0.005 -0.027" rpy="0 0 0" />
<parent link="link_LeftSkeletonPinky4" />
<child link="left_pinky_tip" />
</joint>
<joint name="joint_right_hand" type="fixed">
<origin xyz="0.0097906 -0.039958 -0.03" rpy="0 0 0" />
<parent link="link_RightSkeletonBase" />
<child link="right_hand" />
</joint>
<joint name="joint_left_hand" type="fixed">
<origin xyz="-0.0097906 -0.039958 -0.03" rpy="0 0 0" />
<parent link="link_LeftSkeletonBase" />
<child link="left_hand" />
</joint>
<link
name="Rgamepadbase">
<inertial>
<origin
xyz="0.0031077 0.021669 0.0084989"
rpy="0 0 0" />
<mass
value="0.02843" />
<inertia
ixx="1.9843E-05"
ixy="-3.9906E-07"
ixz="-5.063E-07"
iyy="9.7174E-06"
iyz="-3.9711E-06"
izz="2.0273E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://io_mocap/description/meshes/Rgamepadbase.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
</link>
<link
name="Rgamepad">
<inertial>
<origin
xyz="0.00893 -0.041415 -0.020604"
rpy="0 0 0" />
<mass
value="0.021713" />
<inertia
ixx="4.7609E-06"
ixy="-3.6668E-07"
ixz="-2.4931E-07"
iyy="1.9878E-06"
iyz="-1.3791E-06"
izz="3.9524E-06" />
</inertial>
</link>
<joint name="Rgamebase_joint" type="fixed" >
<origin xyz="0.0097906 -0.039958 0.0172" rpy="0 0 1.4509" />
<parent link="link_RightSkeletonBase" />
<child link="Rgamepadbase" />
</joint>
<joint
name="Rgamepad_joint"
type="fixed">
<origin
xyz="-0.035927 0.0795 0.020469"
rpy="2.8795 0.79734 -2.0538" />
<parent
link="Rgamepadbase" />
<child
link="Rgamepad" />
<axis
xyz="0 0 0" />
</joint>
<link
name="Lgamepadbase">
<inertial>
<origin
xyz="0.0030876 -0.021663 0.0084916"
rpy="0 0 0" />
<mass
value="0.028422" />
<inertia
ixx="1.9837E-05"
ixy="3.9965E-07"
ixz="-5.0714E-07"
iyy="9.714E-06"
iyz="3.9687E-06"
izz="2.0269E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://io_mocap/description/meshes/Lgamepadbase.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
</link>
<link
name="Lgamepad">
<inertial>
<origin
xyz="0.11839 0.017119 0.1301"
rpy="0 0 0" />
<mass
value="0.021713" />
<inertia
ixx="2.7073E-06"
ixy="1.5308E-06"
ixz="-7.3415E-07"
iyy="3.4923E-06"
iyz="6.6424E-07"
izz="4.5015E-06" />
</inertial>
</link>
<joint name="Lgamebase_joint" type="fixed" >
<origin xyz="-0.0097906 -0.039958 0.0172" rpy="0 0 1.6907" />
<parent link="link_LeftSkeletonBase" />
<child link="Lgamepadbase" />
</joint>
<joint
name="Lgamepad_joint"
type="fixed">
<origin
xyz="-0.035948 -0.079502 0.020469"
rpy="2.8795 -0.79734 -1.0878" />
<parent
link="Lgamepadbase" />
<child
link="Lgamepad" />
<axis
xyz="0 0 0" />
</joint>
</robot>