model
This commit is contained in:
parent
51f45f634f
commit
566285b400
|
@ -125,7 +125,7 @@
|
||||||
|
|
||||||
<!-- Joints: main serial chain -->
|
<!-- Joints: main serial chain -->
|
||||||
<joint name="joint_1" type="revolute">
|
<joint name="joint_1" type="revolute">
|
||||||
<limit effort="0" lower="-0.5759" upper="2.6529" velocity="3.1415" />
|
<limit lower="-2.705" upper="2.705" effort="0" velocity="0"/>
|
||||||
<origin rpy="0 0 0" xyz="0.011789 -0.0278 0.26158" />
|
<origin rpy="0 0 0" xyz="0.011789 -0.0278 0.26158" />
|
||||||
<parent link="base_link" />
|
<parent link="base_link" />
|
||||||
<child link="link_1" />
|
<child link="link_1" />
|
||||||
|
@ -133,14 +133,15 @@
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_2" type="revolute">
|
<joint name="joint_2" type="revolute">
|
||||||
<limit effort="0" lower="-1.270" upper="0.590" velocity="3.1415" /> <parent link="link_1" />
|
<limit lower="-2.444" upper="1.134" effort="0" velocity="0"/>
|
||||||
|
<parent link="link_1" />
|
||||||
<child link="link_2" />
|
<child link="link_2" />
|
||||||
<axis xyz="0 -1 0" />
|
<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>
|
||||||
|
|
||||||
<joint name="joint_3" type="revolute">
|
<joint name="joint_3" type="revolute">
|
||||||
<limit effort="0" lower="-0.596" upper="0.873" velocity="3.1415" />
|
<limit lower="-1.309" upper="1.919" effort="0" velocity="0"/>
|
||||||
<parent link="link_2" />
|
<parent link="link_2" />
|
||||||
<child link="link_3" />
|
<child link="link_3" />
|
||||||
<axis xyz="0 -1 0" />
|
<axis xyz="0 -1 0" />
|
||||||
|
@ -148,7 +149,7 @@
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_4" type="revolute">
|
<joint name="joint_4" type="revolute">
|
||||||
<limit effort="0" lower="-2.338" upper="2.338" velocity="3.1415" />
|
<limit lower="-3.142" upper="3.142" effort="0" velocity="0"/>
|
||||||
<parent link="link_3" />
|
<parent link="link_3" />
|
||||||
<child link="link_4" />
|
<child link="link_4" />
|
||||||
<axis xyz="1 0 0" />
|
<axis xyz="1 0 0" />
|
||||||
|
@ -156,15 +157,15 @@
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_5" type="revolute">
|
<joint name="joint_5" type="revolute">
|
||||||
<limit effort="0" lower="-1.149" upper="1.149" velocity="3.1415" />
|
<limit lower="-2.007" upper="2.007" effort="0" velocity="0"/>
|
||||||
<parent link="link_4" />
|
<parent link="link_4" />
|
||||||
<child link="link_5" />
|
<child link="link_5" />
|
||||||
<axis xyz="0 1 0" />
|
<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.000177" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_6" type="revolute">
|
<joint name="joint_6" type="revolute">
|
||||||
<limit effort="0" lower="-7.226" upper="7.226" velocity="3.1415" />
|
<limit lower="-6.283" upper="6.283" effort="0" velocity="0"/>
|
||||||
<parent link="link_5" />
|
<parent link="link_5" />
|
||||||
<child link="link_6" />
|
<child link="link_6" />
|
||||||
<axis xyz="1 0 0" />
|
<axis xyz="1 0 0" />
|
||||||
|
|
Loading…
Reference in New Issue