unitree_ros/robots/g1_description/inspire_hand/FTP_right_hand.urdf

867 lines
33 KiB
Plaintext
Raw Normal View History

2025-03-12 15:19:52 +08:00
<robot name="Rhand">
<mujoco>
<compiler meshdir="meshes" discardvisual="false"/>
</mujoco>
<link name="right_wrist_yaw_link"></link>
<joint name="right_base_joint" type="fixed">
2025-04-10 16:47:15 +08:00
<origin xyz="0.0415 0 0" rpy="0 1.5707963267 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_wrist_yaw_link"/>
<child link="right_base_link"/>
</joint>
<link name="right_base_link">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="4.56066702604653E-05 -0.003106244650993 0.0721752784828355" rpy="0 0 0"/>
<mass value="0.62266"/>
<inertia ixx="0.000238088630601122" ixy="-1.16726665812887E-06" ixz="5.77609124558337E-07" iyy="0.00028210406583092" iyz="1.55368683899448E-05" izz="0.000154836898082308"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_base_link.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_base_link.STL"/>
</geometry>
</collision>
</link>
2025-04-10 16:47:15 +08:00
<link name="right_palm_force_sensor">
<inertial>
<origin xyz="0.000120426871221421 0.000717269582936034 -0.0006928935004962" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="1.792409847502E-07" ixy="3.5297874278755E-10" ixz="-2.06007907879908E-10" iyy="5.01925280756008E-07" iyz="-4.23310809567535E-10" izz="6.80058307355101E-07"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_palm_force_sensor.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_palm_force_sensor.STL"/>
</geometry>
</collision>
</link>
<joint name="right_palm_force_sensor_joint" type="fixed">
<origin xyz="-0.00036819 0.012296 0.1196" rpy="1.5708 0 -3.1416"/>
<parent link="right_base_link"/>
<child link="right_palm_force_sensor"/>
<axis xyz="0 0 0"/>
</joint>
2025-03-12 15:19:52 +08:00
<link name="right_thumb_1">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="-0.000892586815740379 0.000344905600937098 0.00159994421661698" rpy="0 0 0"/>
<mass value="0.00746"/>
<inertia ixx="1.29835194524364E-07" ixy="-5.71160730713237E-09" ixz="1.48758957374632E-08" iyy="1.11222050936534E-07" iyz="-2.10521827472609E-09" izz="7.03400601569091E-08"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_1.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_1_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.0269 0.02101 0.0689" rpy="0 0 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_base_link"/>
<child link="right_thumb_1"/>
<axis xyz="0 0 -1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="1.1641" effort="10" velocity="1"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_thumb_2">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="0.0138310184561186 0.0119153040965892 -0.0066040787609158" rpy="0 0 0"/>
<mass value="0.04264"/>
<inertia ixx="1.07086820134242E-06" ixy="-7.72811128729268E-08" ixz="1.6492356088499E-09" iyy="9.9489890406106E-07" iyz="-1.72519450001931E-09" izz="1.35184010899012E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_2.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_2_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.0079252 0.0090599 0.0052" rpy="1.5708 0 2.8798"/>
2025-03-12 15:19:52 +08:00
<parent link="right_thumb_1"/>
<child link="right_thumb_2"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="0.5864" effort="10" velocity="1"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_thumb_3">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="0.0108798353899717 0.0042597051968735 -0.00764637401672714" rpy="0 0 0"/>
<mass value="0.01501"/>
<inertia ixx="5.19560132472211E-07" ixy="-1.00415069131876E-07" ixz="-9.80140512897539E-11" iyy="5.03378983794322E-07" iyz="-1.59532488112783E-10" izz="5.33618730069293E-07"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_3.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_3.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_3_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="0.031403 0.021069 0.00095" rpy="0 0 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_thumb_2"/>
<child link="right_thumb_3"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="0.5" effort="10" velocity="1"/>
<mimic joint="right_thumb_2_joint" multiplier="0.8024" offset="0"/>
</joint>
<link name="right_thumb_force_sensor_2">
<inertial>
<origin xyz="2.43300294987259E-05 5.45016031029619E-05 -0.00109137669633625" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="3.34747183285769E-10" ixy="-3.83618671521233E-14" ixz="-3.52155403886961E-13" iyy="3.3582079154486E-10" iyz="1.08928107999936E-12" izz="5.8857712310973E-10"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_2.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_force_sensor_2_joint" type="fixed">
<origin xyz="0.011771 0.01699 -0.0077514" rpy="1.8405 -1.5705 3.1416"/>
<parent link="right_thumb_3"/>
<child link="right_thumb_force_sensor_2"/>
<axis xyz="0 0 0"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_thumb_4">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="0.0163213285767181 0.00521948646562768 -0.00735105906992692" rpy="0 0 0"/>
<mass value="0.00972"/>
<inertia ixx="5.94898170313626E-07" ixy="-2.54243319254154E-07" ixz="-3.85279480113408E-11" iyy="7.79213727447204E-07" iyz="1.05044609120841E-10" izz="8.99837239850073E-07"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_4.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_4.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_4_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="0.021903 0.012816 -0.0003" rpy="0 0 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_thumb_3"/>
<child link="right_thumb_4"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="3.14" effort="10" velocity="1"/>
<mimic joint="right_thumb_3_joint" multiplier="0.9487" offset="0"/>
</joint>
<link name="right_thumb_force_sensor_3">
<inertial>
<origin xyz="-1.23775059738263E-05 -0.000195169652742258 -0.000791740559016839" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="5.41310691342173E-09" ixy="6.87296172207439E-13" ixz="6.30644149217552E-13" iyy="2.55911790350329E-09" iyz="3.82480948255569E-11" izz="7.82908815507693E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_3.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_3.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_force_sensor_3_joint" type="fixed">
<origin xyz="0.014598 0.01472 -0.0073103" rpy="-0.20892 -1.5708 -0.81953"/>
<parent link="right_thumb_4"/>
<child link="right_thumb_force_sensor_3"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_thumb_force_sensor_4">
<inertial>
<origin xyz="-7.92360954363081E-07 0.000270176676441192 -0.00100449430451509" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="8.13571079919818E-11" ixy="2.58693510294188E-14" ixz="-1.96984280101514E-14" iyy="1.7077491736553E-10" iyz="-3.77214180289288E-12" izz="2.11640709143909E-10"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_4.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_4.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_force_sensor_4_joint" type="fixed">
<origin xyz="0.028987 0.017301 -0.0073512" rpy="1.6795 1.5708 2.7448"/>
<parent link="right_thumb_4"/>
<child link="right_thumb_force_sensor_4"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_thumb_force_sensor_1">
<inertial>
<origin xyz="1.67085981274823E-05 1.15915239991271E-05 -0.00107125254163185" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="9.01126285102489E-09" ixy="-2.19183765993572E-15" ixz="-2.32024611820209E-12" iyy="4.94554439784859E-09" iyz="1.17775921788887E-11" izz="1.35651458253969E-08"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_1.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_thumb_force_sensor_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_thumb_force_sensor_1_joint" type="fixed">
<origin xyz="0.0087121 0.026305 -0.0067115" rpy="-1.5728 -1.5708 0.35156"/>
<parent link="right_thumb_2"/>
<child link="right_thumb_force_sensor_1"/>
<axis xyz="0 0 0"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_index_1">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="-0.00219417482969622 0.0127409366565626 -0.00664941200246505" rpy="0 0 0"/>
<mass value="0.02841"/>
<inertia ixx="1.13161497176563E-06" ixy="7.33862739323413E-08" ixz="1.02122975969852E-11" iyy="5.50297969803493E-07" iyz="2.465893504551E-11" izz="1.17483803325344E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_1.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_index_1_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.038679 0.00056467 0.1564" rpy="1.6057 0 -1.5708"/>
2025-03-12 15:19:52 +08:00
<parent link="right_base_link"/>
<child link="right_index_1"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="1.4381" effort="10" velocity="1"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_index_2">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="0.00053282674431529 0.0253434850963997 -0.00609291472256712" rpy="0 0 0"/>
<mass value="0.01218"/>
<inertia ixx="2.11107718074946E-06" ixy="3.78350673743143E-07" ixz="-4.27563147991044E-10" iyy="3.7048516715658E-07" iyz="2.82151424550267E-09" izz="2.14315437386293E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_2.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_index_2_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.0034259 0.032596 -0.00055" rpy="0 0 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_index_1"/>
<child link="right_index_2"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="3.14" effort="10" velocity="1"/>
<mimic joint="right_index_1_joint" multiplier="1.0843" offset="0"/>
</joint>
<link name="right_index_force_sensor_2">
<inertial>
<origin xyz="3.91105790090857E-06 0.000206428506730846 -0.000722888656592813" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="4.79878645065383E-09" ixy="-8.64076408119868E-11" ixz="-1.50330115198978E-12" iyy="2.43958893457374E-09" iyz="-3.05132448820234E-11" izz="7.12570334555721E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_force_sensor_2.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_force_sensor_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_index_force_sensor_2_joint" type="fixed">
<origin xyz="-0.0081655 0.037446 -0.0060795" rpy="-1.5708 -1.5337 1.9196"/>
<parent link="right_index_2"/>
<child link="right_index_force_sensor_2"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_index_force_sensor_3">
<inertial>
<origin xyz="-2.48722057788475E-05 -0.000345285689256153 -0.00133800038179009" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="1.31974821284448E-10" ixy="5.65060068039544E-12" ixz="7.79117122469869E-13" iyy="2.53430134807533E-10" iyz="9.12198063131294E-12" izz="2.8053351791299E-10"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_force_sensor_3.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_force_sensor_3.STL"/>
</geometry>
</collision>
</link>
<joint name="right_index_force_sensor_3_joint" type="fixed">
<origin xyz="-0.0086237 0.052572 -0.0060954" rpy="-1.5708 -1.5252 0.87237"/>
<parent link="right_index_2"/>
<child link="right_index_force_sensor_3"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_index_force_sensor_1">
<inertial>
<origin xyz="4.50639917342482E-06 0.000116571661332499 -0.000567443126962358" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="3.38028798502951E-09" ixy="-5.04640338896759E-11" ixz="-2.15701714440087E-13" iyy="1.96412698995832E-09" iyz="-5.48195334354584E-12" izz="5.28079732652296E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_force_sensor_1.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_index_force_sensor_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_index_force_sensor_1_joint" type="fixed">
<origin xyz="-0.012046 0.019649 -0.006651" rpy="-1.5708 -1.5351 1.3587"/>
<parent link="right_index_1"/>
<child link="right_index_force_sensor_1"/>
<axis xyz="0 0 0"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_middle_1">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="-0.00219417478814514 0.0127409366268324 -0.00664941207814898" rpy="0 0 0"/>
<mass value="0.02841"/>
<inertia ixx="1.1316149557554E-06" ixy="7.33862743651549E-08" ixz="1.02132031162304E-11" iyy="5.50297969652712E-07" iyz="2.46615051816588E-11" izz="1.17483802522199E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_1.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_middle_1_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.0171 0.00056467 0.157" rpy="1.5708 0 -1.5708"/>
2025-03-12 15:19:52 +08:00
<parent link="right_base_link"/>
<child link="right_middle_1"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="1.4381" effort="10" velocity="1"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_middle_2">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="-9.21583803522863E-05 0.0270332758922563 -0.00610054154137712" rpy="0 0 0"/>
<mass value="0.01561"/>
<inertia ixx="2.58635805719435E-06" ixy="4.53231180080783E-07" ixz="-7.60066680662939E-12" iyy="4.10296161873934E-07" iyz="7.98220547148583E-11" izz="2.62934430889061E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_2.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_middle_2_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.0034259 0.032596 -0.00055" rpy="0 0 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_middle_1"/>
<child link="right_middle_2"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="3.14" effort="10" velocity="1"/>
<mimic joint="right_middle_1_joint" multiplier="1.0843" offset="0"/>
</joint>
<link name="right_middle_force_sensor_2">
<inertial>
<origin xyz="-3.55652627983399E-07 2.88666331397097E-05 -0.000722235489778011" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="5.0422606271269E-09" ixy="3.96627458520336E-13" ixz="-3.26041478715661E-14" iyy="2.56807850635636E-09" iyz="3.53736208701199E-12" izz="7.49563436241948E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_force_sensor_2.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_force_sensor_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_middle_force_sensor_2_joint" type="fixed">
<origin xyz="-0.0090859 0.040963 -0.0061003" rpy="2.7687 -1.5708 3.885"/>
<parent link="right_middle_2"/>
<child link="right_middle_force_sensor_2"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_middle_force_sensor_3">
<inertial>
<origin xyz="6.04731043574169E-08 -0.00036544534557964 -0.00127683945630336" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="1.27227764572837E-10" ixy="1.00476590749141E-14" ixz="8.57880628295176E-15" iyy="2.43691164484046E-10" iyz="7.61272996067342E-12" izz="2.7587517056304E-10"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_force_sensor_3.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_force_sensor_3.STL"/>
</geometry>
</collision>
</link>
<joint name="right_middle_force_sensor_3_joint" type="fixed">
<origin xyz="-0.0098294 0.056051 -0.0061006" rpy="2.4672 -1.5708 3.14"/>
<parent link="right_middle_2"/>
<child link="right_middle_force_sensor_3"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_middle_force_sensor_1">
<inertial>
<origin xyz="3.42843697213185E-07 0.000116657509605197 -0.000567442695803486" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="3.38208410519618E-09" ixy="1.8756957436983E-13" ixz="-1.99647221364603E-14" iyy="1.96233204624223E-09" iyz="-5.48580562274466E-12" izz="5.2807983995112E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_force_sensor_1.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_middle_force_sensor_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_middle_force_sensor_1_joint" type="fixed">
<origin xyz="-0.012046 0.019649 -0.006651" rpy="2.9295 -1.5708 3.14"/>
<parent link="right_middle_1"/>
<child link="right_middle_force_sensor_1"/>
<axis xyz="0 0 0"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_ring_1">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="-0.00219417465246989 0.0127409362160862 -0.0066494113506478" rpy="0 0 0"/>
<mass value="0.02841"/>
<inertia ixx="1.13161521046633E-06" ixy="7.33862976638613E-08" ixz="1.02299251281265E-11" iyy="5.50298017624686E-07" iyz="2.46423372584933E-11" izz="1.17483820891763E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_1.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_ring_1_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="0.0045302 0.00056467 0.15683" rpy="1.5184 0 -1.5708"/>
2025-03-12 15:19:52 +08:00
<parent link="right_base_link"/>
<child link="right_ring_1"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="1.4381" effort="10" velocity="1"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_ring_2">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="0.000532825578113461 0.02534346612146 -0.00609293344206238" rpy="0 0 0"/>
<mass value="0.01281"/>
<inertia ixx="2.1110771068108E-06" ixy="3.78350047415621E-07" ixz="-4.27359495460949E-10" iyy="3.70485089846105E-07" iyz="2.82233622984192E-09" izz="2.14315369799671E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_2.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_ring_2_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.0034259 0.032596 -0.00055" rpy="0 0 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_ring_1"/>
<child link="right_ring_2"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="3.14" effort="10" velocity="1"/>
<mimic joint="right_ring_1_joint" multiplier="1.0843" offset="0"/>
</joint>
<link name="right_ring_force_sensor_2">
<inertial>
<origin xyz="-1.52436836100122E-05 0.000205901966578506 -0.000722888420897932" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="4.79446001367797E-09" ixy="1.32867587230544E-10" ixz="1.3319969497832E-12" iyy="2.44391505492957E-09" iyz="-3.05212434039785E-11" izz="7.12570290551646E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_force_sensor_2.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_force_sensor_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_ring_force_sensor_2_joint" type="fixed">
<origin xyz="-0.00816549212353353 0.0374457610846523 -0.00607949056508933" rpy="1.57079632679487 -1.51508890383765 -1.22202982373572"/>
<parent link="right_ring_2"/>
<child link="right_ring_force_sensor_2"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_ring_force_sensor_3">
<inertial>
<origin xyz="1.45480090249107E-05 -0.000345868489067203 -0.00133799622683203" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="1.32268380918037E-10" ixy="-8.21005557691383E-12" ixz="-2.63863504125309E-13" iyy="2.53139740379503E-10" iyz="9.1510626727994E-12" izz="2.80536239837899E-10"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_force_sensor_3.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_force_sensor_3.STL"/>
</geometry>
</collision>
</link>
<joint name="right_ring_force_sensor_3_joint" type="fixed">
<origin xyz="-0.00862372785817732 0.0525719273258207 -0.00609538761271226" rpy="1.57079632679487 -1.50247215376038 -2.26922737493233"/>
<parent link="right_ring_2"/>
<child link="right_ring_force_sensor_3"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_ring_force_sensor_1">
<inertial>
<origin xyz="-5.90327958142033E-06 0.000116509445804644 -0.000567443259521572" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="3.37799540185096E-09" ixy="7.60796091703617E-11" ixz="2.73854397843076E-13" iyy="1.96641957767428E-09" iyz="-5.47947431188363E-12" izz="5.28079735826682E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_force_sensor_1.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_ring_force_sensor_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_ring_force_sensor_1_joint" type="fixed">
<origin xyz="-0.0120461582060112 0.019648547178991 -0.00665098451502209" rpy="1.57079632679491 -1.51723862304532 -1.78288465285967"/>
<parent link="right_ring_1"/>
<child link="right_ring_force_sensor_1"/>
<axis xyz="0 0 0"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_little_1">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="-0.00219418424084009 0.0127409391731467 -0.00664940009923338" rpy="0 0 0"/>
<mass value="0.02841"/>
<inertia ixx="1.13161476879442E-06" ixy="7.33861803205532E-08" ixz="9.70201262730489E-12" iyy="5.50297118553785E-07" iyz="2.47668324333468E-11" izz="1.17483808711618E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_1.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_little_1_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="0.025916 0.00056467 0.15365" rpy="1.4661 0 -1.5708"/>
2025-03-12 15:19:52 +08:00
<parent link="right_base_link"/>
<child link="right_little_1"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="1.4381" effort="10" velocity="1"/>
2025-03-12 15:19:52 +08:00
</joint>
<link name="right_little_2">
<inertial>
2025-04-10 16:47:15 +08:00
<origin xyz="0.00142962322858008 0.0206390061213492 -0.00609937271859847" rpy="0 0 0"/>
<mass value="0.00957"/>
<inertia ixx="1.1469386346846E-06" ixy="2.22234007983847E-07" ixz="3.68343779413029E-11" iyy="2.66181840844389E-07" iyz="-2.048922749441E-11" izz="1.15056368955352E-06"/>
2025-03-12 15:19:52 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_2.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_little_2_joint" type="revolute">
2025-04-10 16:47:15 +08:00
<origin xyz="-0.0034259 0.032596 -0.00055" rpy="0 0 0"/>
2025-03-12 15:19:52 +08:00
<parent link="right_little_1"/>
<child link="right_little_2"/>
<axis xyz="0 0 1"/>
2025-04-10 16:47:15 +08:00
<limit lower="0" upper="3.14" effort="10" velocity="1"/>
<mimic joint="right_little_1_joint" multiplier="1.0843" offset="0"/>
</joint>
<link name="right_little_force_sensor_2">
<inertial>
<origin xyz="1.83850807690782E-05 -0.000118792499944516 -0.00077353663965421" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="5.36105565367509E-09" ixy="2.9087102385881E-10" ixz="-4.23704440233772E-12" iyy="2.78924633862048E-09" iyz="3.60734545957644E-11" izz="8.01055296833179E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_force_sensor_2.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_force_sensor_2.STL"/>
</geometry>
</collision>
</link>
<joint name="right_little_force_sensor_2_joint" type="fixed">
<origin xyz="-0.00645123763174135 0.0276833479200767 -0.00611719352979621" rpy="1.57079632679488 -1.45969392221055 -1.22888814145719"/>
<parent link="right_little_2"/>
<child link="right_little_force_sensor_2"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_little_force_sensor_3">
<inertial>
<origin xyz="6.36863053951123E-05 -0.000437236774208316 -0.00112814037373121" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="1.11592356002466E-10" ixy="-1.48925479775264E-11" ixz="-1.18387481927136E-12" iyy="2.17209112811676E-10" iyz="8.07880135891967E-12" izz="2.52055535156648E-10"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_force_sensor_3.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_force_sensor_3.STL"/>
</geometry>
</collision>
</link>
<joint name="right_little_force_sensor_3_joint" type="fixed">
<origin xyz="-0.00639723214432697 0.042706921918282 -0.00611537168168175" rpy="1.5707963267949 -1.43362674619531 -2.2760856926538"/>
<parent link="right_little_2"/>
<child link="right_little_force_sensor_3"/>
<axis xyz="0 0 0"/>
</joint>
<link name="right_little_force_sensor_1">
<inertial>
<origin xyz="-1.2130080955873E-05 0.000116026903212899 -0.00056744299424992" rpy="0 0 0"/>
<mass value="0.001"/>
<inertia ixx="3.3658199564233E-09" ixy="1.51080971417152E-10" ixz="5.66657100478518E-13" iyy="1.97859528185445E-09" iyz="-5.45672948532754E-12" izz="5.28079755559196E-09"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_force_sensor_1.STL"/>
</geometry>
<material name="">
<color rgba="0.411764705882353 0.411764705882353 0.411764705882353 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="meshes/right_little_force_sensor_1.STL"/>
</geometry>
</collision>
</link>
<joint name="right_little_force_sensor_1_joint" type="fixed">
<origin xyz="-0.0120461582060113 0.0196485471789908 -0.00665098451502223" rpy="1.5707963267949 -1.4636944932668 -1.78288465285966"/>
<parent link="right_little_1"/>
<child link="right_little_force_sensor_1"/>
<axis xyz="0 0 0"/>
2025-03-12 15:19:52 +08:00
</joint>
</robot>