update z1.urdf
This commit is contained in:
parent
15e36e09c5
commit
f10d1c6add
|
@ -41,7 +41,7 @@
|
|||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00334984 -0.00013615 0.02495843"/>
|
||||
<mass value="0.47247481"/>
|
||||
<inertia ixx="0.00037937" ixy="3.5e-07" ixz="1.037e-05" iyy="0.00041521" iyz="9.9e-07" izz="0.00053066"/>
|
||||
<inertia ixx="0.00037937" ixy="-3.5e-07" ixz="-1.037e-05" iyy="0.00041521" iyz="-9.9e-07" izz="0.00053066"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint1" type="revolute">
|
||||
|
@ -50,7 +50,7 @@
|
|||
<child link="link01"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-2.6179938779914944" upper="2.6179938779914944" velocity="10"/>
|
||||
<limit effort="30.0" lower="-2.6179938779914944" upper="2.6179938779914944" velocity="3.1415"/>
|
||||
</joint>
|
||||
<link name="link01">
|
||||
<visual>
|
||||
|
@ -62,7 +62,7 @@
|
|||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="2.47e-06 -0.00025198 0.02317169"/>
|
||||
<mass value="0.67332551"/>
|
||||
<inertia ixx="0.00128328" ixy="6e-08" ixz="4e-07" iyy="0.00071931" iyz="-5e-07" izz="0.00083936"/>
|
||||
<inertia ixx="0.00128328" ixy="-6e-08" ixz="-4e-07" iyy="0.00071931" iyz="5e-07" izz="0.00083936"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint2" type="revolute">
|
||||
|
@ -71,7 +71,7 @@
|
|||
<child link="link02"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="2.0" friction="2.0"/>
|
||||
<limit effort="60.0" lower="0.0" upper="2.9670597283903604" velocity="10"/>
|
||||
<limit effort="60.0" lower="0.0" upper="2.9670597283903604" velocity="3.1415"/>
|
||||
</joint>
|
||||
<link name="link02">
|
||||
<visual>
|
||||
|
@ -101,7 +101,7 @@
|
|||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.11012601 0.00240029 0.00158266"/>
|
||||
<mass value="1.19132258"/>
|
||||
<inertia ixx="0.00102138" ixy="-0.00062358" ixz="-5.13e-06" iyy="0.02429457" iyz="2.1e-06" izz="0.02466114"/>
|
||||
<inertia ixx="0.00102138" ixy="0.00062358" ixz="5.13e-06" iyy="0.02429457" iyz="-2.1e-06" izz="0.02466114"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint3" type="revolute">
|
||||
|
@ -110,7 +110,7 @@
|
|||
<child link="link03"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-2.8797932657906435" upper="0.0" velocity="10"/>
|
||||
<limit effort="30.0" lower="-2.8797932657906435" upper="0.0" velocity="3.1415"/>
|
||||
</joint>
|
||||
<link name="link03">
|
||||
<visual>
|
||||
|
@ -134,7 +134,7 @@
|
|||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.10609208 -0.00541815 0.03476383"/>
|
||||
<mass value="0.83940874"/>
|
||||
<inertia ixx="0.00108061" ixy="8.669e-05" ixz="0.00208102" iyy="0.00954238" iyz="1.332e-05" izz="0.00886621"/>
|
||||
<inertia ixx="0.00108061" ixy="-8.669e-05" ixz="-0.00208102" iyy="0.00954238" iyz="-1.332e-05" izz="0.00886621"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint4" type="revolute">
|
||||
|
@ -143,7 +143,7 @@
|
|||
<child link="link04"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-1.5184364492350666" upper="1.5184364492350666" velocity="10"/>
|
||||
<limit effort="30.0" lower="-1.5184364492350666" upper="1.5184364492350666" velocity="3.1415"/>
|
||||
</joint>
|
||||
<link name="link04">
|
||||
<visual>
|
||||
|
@ -161,7 +161,7 @@
|
|||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.04366681 0.00364738 -0.00170192"/>
|
||||
<mass value="0.56404563"/>
|
||||
<inertia ixx="0.00031576" ixy="-8.13e-05" ixz="-4.091e-05" iyy="0.00092996" iyz="5.96e-06" izz="0.00097912"/>
|
||||
<inertia ixx="0.00031576" ixy="8.13e-05" ixz="4.091e-05" iyy="0.00092996" iyz="-5.96e-06" izz="0.00097912"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint5" type="revolute">
|
||||
|
@ -170,7 +170,7 @@
|
|||
<child link="link05"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-1.3439035240356338" upper="1.3439035240356338" velocity="10"/>
|
||||
<limit effort="30.0" lower="-1.3439035240356338" upper="1.3439035240356338" velocity="3.1415"/>
|
||||
</joint>
|
||||
<link name="link05">
|
||||
<visual>
|
||||
|
@ -182,7 +182,7 @@
|
|||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.03121533 0.0 0.00646316"/>
|
||||
<mass value="0.38938492"/>
|
||||
<inertia ixx="0.00017605" ixy="-4e-07" ixz="-5.689e-05" iyy="0.00055896" iyz="1.3e-07" izz="0.0005386"/>
|
||||
<inertia ixx="0.00017605" ixy="4e-07" ixz="5.689e-05" iyy="0.00055896" iyz="-1.3e-07" izz="0.0005386"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint6" type="revolute">
|
||||
|
@ -191,7 +191,7 @@
|
|||
<child link="link06"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
<limit effort="30.0" lower="-2.792526803190927" upper="2.792526803190927" velocity="10"/>
|
||||
<limit effort="30.0" lower="-2.792526803190927" upper="2.792526803190927" velocity="3.1415"/>
|
||||
</joint>
|
||||
<link name="link06">
|
||||
<visual>
|
||||
|
@ -209,7 +209,7 @@
|
|||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0241569 -0.00017355 -0.00143876"/>
|
||||
<mass value="0.28875807"/>
|
||||
<inertia ixx="0.00018328" ixy="-1.22e-06" ixz="-5.4e-07" iyy="0.0001475" iyz="-8e-08" izz="0.0001468"/>
|
||||
<inertia ixx="0.00018328" ixy="1.22e-06" ixz="5.4e-07" iyy="0.0001475" iyz="8e-08" izz="0.0001468"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<transmission name="JointTrans1">
|
||||
|
|
Loading…
Reference in New Issue