-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathxarm6_nogripper.srdf
52 lines (52 loc) · 2.52 KB
/
xarm6_nogripper.srdf
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from src/xarm_ros/xarm_description/srdf/xarm.srdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="xarm6">
<group name="xarm6">
<joint name="world_joint"/>
<joint name="joint1"/>
<joint name="joint2"/>
<joint name="joint3"/>
<joint name="joint4"/>
<joint name="joint5"/>
<joint name="joint6"/>
</group>
<group name="tool_end">
<joint name="joint_eef"/>
</group>
<end_effector group="tool_end" name="end_effector" parent_link="link6"/>
<!-- GROUP STATES, Purpose, Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms' -->
<group_state group="xarm6" name="home">
<joint name="joint1" value="0"/>
<joint name="joint2" value="0"/>
<joint name="joint3" value="0"/>
<joint name="joint4" value="0"/>
<joint name="joint5" value="0"/>
<joint name="joint6" value="0"/>
</group_state>
<group_state group="xarm6" name="hold-up">
<joint name="joint1" value="0"/>
<joint name="joint2" value="0"/>
<joint name="joint3" value="0"/>
<joint name="joint4" value="0"/>
<joint name="joint5" value="-1.5708"/>
<joint name="joint6" value="0"/>
</group_state>
<disable_collisions link1="link1" link2="link2" reason="Adjacent"/>
<disable_collisions link1="link1" link2="link3" reason="Never"/>
<disable_collisions link1="link1" link2="link_base" reason="Adjacent"/>
<disable_collisions link1="link2" link2="link3" reason="Adjacent"/>
<disable_collisions link1="link2" link2="link4" reason="Never"/>
<disable_collisions link1="link2" link2="link_base" reason="Never"/>
<disable_collisions link1="link3" link2="link4" reason="Adjacent"/>
<disable_collisions link1="link3" link2="link5" reason="Never"/>
<disable_collisions link1="link3" link2="link6" reason="Never"/>
<disable_collisions link1="link4" link2="link5" reason="Adjacent"/>
<disable_collisions link1="link4" link2="link6" reason="Never"/>
<disable_collisions link1="link5" link2="link6" reason="Adjacent"/>
<disable_collisions link1="link3" link2="link_eef" reason="Never"/>
<disable_collisions link1="link5" link2="link_eef" reason="Never"/>
<disable_collisions link1="link6" link2="link_eef" reason="Adjacent"/>
</robot>