work model
This commit is contained in:
parent
d75007d604
commit
51f45f634f
|
@ -125,51 +125,50 @@
|
|||
|
||||
<!-- Joints: main serial chain -->
|
||||
<joint name="joint_1" type="revolute">
|
||||
<limit effort="0" lower="-2.7925" upper="2.7925" velocity="3.1415" />
|
||||
<origin rpy="0 0 0" xyz="-0.011789 0.0278 0.26158" />
|
||||
<limit effort="0" lower="-0.5759" upper="2.6529" velocity="3.1415" />
|
||||
<origin rpy="0 0 0" xyz="0.011789 -0.0278 0.26158" />
|
||||
<parent link="base_link" />
|
||||
<child link="link_1" />
|
||||
<axis xyz="0 0 1" />
|
||||
</joint>
|
||||
|
||||
<joint name="joint_2" type="revolute">
|
||||
<limit effort="0" lower="-0.5759" upper="2.6529" velocity="3.1415" />
|
||||
<parent link="link_1" />
|
||||
<limit effort="0" lower="-1.270" upper="0.590" velocity="3.1415" /> <parent link="link_1" />
|
||||
<child link="link_2" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<origin rpy="0 0 0" xyz="-0.168621 0.103 0.23445" />
|
||||
<origin rpy="0 0 0" xyz="0.168621 -0.103 0.23445" />
|
||||
</joint>
|
||||
|
||||
<joint name="joint_3" type="revolute">
|
||||
<limit effort="0" lower="-2.6145" upper="2.8797" velocity="3.9269" />
|
||||
<limit effort="0" lower="-0.596" upper="0.873" velocity="3.1415" />
|
||||
<parent link="link_2" />
|
||||
<child link="link_3" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<origin rpy="0 0 0" xyz="0.35988 -0.00232 0.63457" />
|
||||
<origin rpy="0 0 0" xyz="0.006871 0.002321 0.729516" />
|
||||
</joint>
|
||||
|
||||
<joint name="joint_4" type="revolute">
|
||||
<limit effort="0" lower="-3.3161" upper="3.3161" velocity="6.9813" />
|
||||
<limit effort="0" lower="-2.338" upper="2.338" velocity="3.1415" />
|
||||
<parent link="link_3" />
|
||||
<child link="link_4" />
|
||||
<axis xyz="0 0 1" />
|
||||
<origin rpy="0 0 0" xyz="-0.23985 -0.101766 0.0983" />
|
||||
<axis xyz="1 0 0" />
|
||||
<origin rpy="0 0 0" xyz="0.240065 0.101766 0.097739" />
|
||||
</joint>
|
||||
|
||||
<joint name="joint_5" type="revolute">
|
||||
<limit effort="0" lower="-2.0943" upper="2.0943" velocity="5.7595" />
|
||||
<limit effort="0" lower="-1.149" upper="1.149" velocity="3.1415" />
|
||||
<parent link="link_4" />
|
||||
<child link="link_5" />
|
||||
<axis xyz="0 1 0" />
|
||||
<origin rpy="0 0 0" xyz="-0.867755 -0.037912 0.0021" />
|
||||
<origin rpy="0 0 0" xyz="0.867755 -0.037912 0.0021" />
|
||||
</joint>
|
||||
|
||||
<joint name="joint_6" type="revolute">
|
||||
<limit effort="0" lower="-6.2831" upper="6.2831" velocity="8.3775" />
|
||||
<limit effort="0" lower="-7.226" upper="7.226" velocity="3.1415" />
|
||||
<parent link="link_5" />
|
||||
<child link="link_6" />
|
||||
<axis xyz="0 0 1" />
|
||||
<origin rpy="0 0 0" xyz="-0.12086 0.039025 0.0002" />
|
||||
<axis xyz="1 0 0" />
|
||||
<origin rpy="0 0 0" xyz="0.098817 -0.039029 -0.000419" />
|
||||
</joint>
|
||||
|
||||
</robot>
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Loading…
Reference in New Issue