minor adjustments all over the place.
This commit is contained in:
@@ -27,7 +27,7 @@
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.043517 0.000000 0.054914"/>
|
||||
<mass value="0.1"/>
|
||||
<mass value="6"/>
|
||||
<inertia ixx="1.277905" ixy="0.0" ixz="0.138279" iyy="3.070705" iyz="0.0" izz="3.284356"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -45,7 +45,7 @@
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.005 0.08"/>
|
||||
<mass value="0.1"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.32666666666667" ixy="0.0" ixz="0.0" iyy="0.32666666666667" iyz="0.0" izz="0.25"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -62,7 +62,7 @@
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.050000 0.150000"/>
|
||||
<mass value="0.1"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="8.266347" ixy="0.0" ixz="0.0" iyy="8.647519" iyz="0.0" izz="8.647519"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -80,7 +80,7 @@
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.07 0.025"/>
|
||||
<mass value="0.1"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.5" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="0.25"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -97,7 +97,7 @@
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.037363 0.086674"/>
|
||||
<mass value="0.1"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="1.431738" ixy="0.0" ixz="0.0" iyy="1.131426" iyz="-0.342192" izz="0.807202"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -114,7 +114,7 @@
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.055000 0.021413"/>
|
||||
<mass value="0.1"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.362124" ixy="0.0" ixz="0.0" iyy="0.343531" iyz="0.0" izz="0.283368"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -131,7 +131,7 @@
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.015462 0.040000"/>
|
||||
<mass value="0.1"/>
|
||||
<mass value="0.8"/>
|
||||
<inertia ixx="0.228470" ixy="0.0" ixz="0.0" iyy="0.137641" iyz="0.0" izz="0.252003"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -155,31 +155,31 @@
|
||||
<parent link="base_bottom"/>
|
||||
<child link="base_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
<dynamics damping="10.0" friction="0.1"/>
|
||||
<limit effort="300" velocity="3.49065850399"/>
|
||||
<dynamics damping="30.0" friction="0.1"/>
|
||||
</joint>
|
||||
<joint name="base_link1_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.080499 0.092997"/>
|
||||
<parent link="base_top"/>
|
||||
<child link="link1_full"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" lower="-2.2689280275926" upper="2.4434609527921" velocity="1.7453292519943"/>
|
||||
<dynamics damping="10.0" friction="0.1"/>
|
||||
<limit effort="300" lower="-2.2689280275926" upper="2.4434609527921" velocity="3.49065850399"/>
|
||||
<dynamics damping="30.0" friction="0.1"/>
|
||||
</joint>
|
||||
<joint name="link1_link2_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.3"/>
|
||||
<parent link="link1_full"/>
|
||||
<child link="link2_bottom"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" lower="-2.6179938779915" upper="2.6179938779915" velocity="1.7453292519943"/>
|
||||
<dynamics damping="10.0" friction="0.1"/>
|
||||
<limit effort="200" lower="-2.6179938779915" upper="2.6179938779915" velocity="3.49065850399"/>
|
||||
<dynamics damping="20.0" friction="0.1"/>
|
||||
</joint>
|
||||
<joint name="link2_rot" type="continuous">
|
||||
<origin rpy="0 0 0" xyz="0 0.080501 0.120502"/>
|
||||
<parent link="link2_bottom"/>
|
||||
<child link="link2_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
<limit effort="100" velocity="5.23598775598"/>
|
||||
<dynamics damping="10.0" friction="0.1"/>
|
||||
</joint>
|
||||
<joint name="link2_link3_joint" type="continuous">
|
||||
@@ -187,16 +187,16 @@
|
||||
<parent link="link2_top"/>
|
||||
<child link="link3_bottom"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
<dynamics damping="10.0" friction="0.1"/>
|
||||
<limit effort="50" velocity="5.23598775598"/>
|
||||
<dynamics damping="5.0" friction="0.1"/>
|
||||
</joint>
|
||||
<joint name="link3_rot" type="continuous">
|
||||
<origin rpy="0 0 0" xyz="0 -0.055001 0.085501"/>
|
||||
<parent link="link3_bottom"/>
|
||||
<child link="link3_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
<dynamics damping="10.0" friction="0.1"/>
|
||||
<limit effort="50" velocity="6.98131700798"/>
|
||||
<dynamics damping="5.0" friction="0.1"/>
|
||||
</joint>
|
||||
<transmission name="trans_base_rot">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
|
||||
Reference in New Issue
Block a user