/
xarm6_with_gripper.srdf
124 lines (123 loc) · 7.62 KB
/
xarm6_with_gripper.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
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
<?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="UF_ROBOT">
<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"/>
<joint name="gripper_fix"/>
<joint name="joint_tcp"/>
</group>
<!-- 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>
<group name="xarm_gripper">
<link name="xarm_gripper_base_link"/>
<link name="left_outer_knuckle"/>
<link name="left_finger"/>
<link name="left_inner_knuckle"/>
<link name="right_inner_knuckle"/>
<link name="right_outer_knuckle"/>
<link name="right_finger"/>
<link name="link_tcp"/>
<joint name="drive_joint"/>
</group>
<group_state group="xarm_gripper" name="open">
<joint name="drive_joint" value="0"/>
</group_state>
<group_state group="xarm_gripper" name="close">
<joint name="drive_joint" value="0.85"/>
</group_state>
<!-- END EFFECTOR, Purpose, Represent information about an end effector. -->
<end_effector group="xarm_gripper" name="xarm_gripper" parent_link="link_tcp"/>
<!--PASSIVE JOINT, Purpose, this element is used to mark joints that are not actuated-->
<passive_joint name="left_finger_joint"/>
<passive_joint name="left_inner_knuckle_joint"/>
<passive_joint name="right_inner_knuckle_joint"/>
<passive_joint name="right_outer_knuckle_joint"/>
<passive_joint name="right_finger_joint"/>
<!-- DISABLE COLLISIONS, By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="left_finger" link2="left_inner_knuckle" reason="Default"/>
<disable_collisions link1="left_finger" link2="left_outer_knuckle" reason="Adjacent"/>
<disable_collisions link1="left_finger" link2="link4" reason="Never"/>
<disable_collisions link1="left_finger" link2="link5" reason="Never"/>
<disable_collisions link1="left_finger" link2="link6" reason="Never"/>
<disable_collisions link1="left_finger" link2="right_finger" reason="Never"/>
<disable_collisions link1="left_finger" link2="right_inner_knuckle" reason="Never"/>
<disable_collisions link1="left_finger" link2="right_outer_knuckle" reason="Never"/>
<disable_collisions link1="left_finger" link2="xarm_gripper_base_link" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="left_outer_knuckle" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="link4" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="link5" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="link6" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="right_finger" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="right_inner_knuckle" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="right_outer_knuckle" reason="Never"/>
<disable_collisions link1="left_inner_knuckle" link2="xarm_gripper_base_link" reason="Adjacent"/>
<disable_collisions link1="left_outer_knuckle" link2="link5" reason="Never"/>
<disable_collisions link1="left_outer_knuckle" link2="link6" reason="Never"/>
<disable_collisions link1="left_outer_knuckle" link2="right_finger" reason="Never"/>
<disable_collisions link1="left_outer_knuckle" link2="right_inner_knuckle" reason="Never"/>
<disable_collisions link1="left_outer_knuckle" link2="right_outer_knuckle" reason="Never"/>
<disable_collisions link1="left_outer_knuckle" link2="xarm_gripper_base_link" reason="Adjacent"/>
<disable_collisions link1="link_eef" link2="left_finger" reason="Never"/>
<disable_collisions link1="link_eef" link2="left_inner_knuckle" reason="Never"/>
<disable_collisions link1="link_eef" link2="left_outer_knuckle" reason="Never"/>
<disable_collisions link1="link4" link2="right_finger" reason="Never"/>
<disable_collisions link1="link4" link2="right_inner_knuckle" reason="Never"/>
<disable_collisions link1="link5" link2="link6" reason="Adjacent"/>
<disable_collisions link1="link5" link2="right_finger" reason="Never"/>
<disable_collisions link1="link5" link2="right_inner_knuckle" reason="Never"/>
<disable_collisions link1="link5" link2="right_outer_knuckle" reason="Never"/>
<disable_collisions link1="link5" link2="xarm_gripper_base_link" reason="Never"/>
<disable_collisions link1="link6" link2="right_finger" reason="Never"/>
<disable_collisions link1="link6" link2="right_inner_knuckle" reason="Never"/>
<disable_collisions link1="link6" link2="right_outer_knuckle" reason="Never"/>
<disable_collisions link1="link6" link2="xarm_gripper_base_link" reason="Never"/>
<disable_collisions link1="right_finger" link2="right_inner_knuckle" reason="Default"/>
<disable_collisions link1="right_finger" link2="right_outer_knuckle" reason="Adjacent"/>
<disable_collisions link1="right_finger" link2="xarm_gripper_base_link" reason="Never"/>
<disable_collisions link1="right_inner_knuckle" link2="right_outer_knuckle" reason="Never"/>
<disable_collisions link1="right_inner_knuckle" link2="xarm_gripper_base_link" reason="Adjacent"/>
<disable_collisions link1="right_outer_knuckle" link2="xarm_gripper_base_link" reason="Adjacent"/>
<disable_collisions link1="link_eef" link2="xarm_gripper_base_link" reason="Adjacent"/>
<disable_collisions link1="link_eef" link2="right_finger" reason="Never"/>
<disable_collisions link1="link_eef" link2="right_inner_knuckle" reason="Never"/>
<disable_collisions link1="link_eef" link2="right_outer_knuckle" reason="Never"/>
<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>