-
Notifications
You must be signed in to change notification settings - Fork 27
/
panda.ros2_control
207 lines (200 loc) · 8.05 KB
/
panda.ros2_control
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
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
<?xml version="1.0"?>
<!-- Macros that add ros2 control for Franka Emika Panda -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- -->
<!-- Properties -->
<!-- -->
<xacro:property name="default_initial_positions_file" value="$(find panda_description)/config/initial_joint_positions.yaml"/>
<!-- -->
<!-- Macro -->
<!-- -->
<xacro:macro name="ros2_control_panda_arm" params="
name:=panda_arm_system
prefix:=panda_
plugin:=fake
command_interface:=effort
initial_positions_file:=${default_initial_positions_file}
">
<xacro:property name="initial_positions" value="${load_yaml(initial_positions_file)['initial_joint_positions']['panda_arm']}"/>
<ros2_control name="${name}" type="system">
<hardware>
<xacro:if value="${plugin == 'fake'}">
<plugin>fake_components/GenericSystem</plugin>
</xacro:if>
<xacro:if value="${plugin == 'ign'}">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:if value="${plugin == 'real'}">
<xacro:ERROR_ros2_control_for_real_robot_unimplemented/>
</xacro:if>
<xacro:unless value="${plugin == 'fake' or plugin == 'ign' or plugin == 'real'}">
<plugin>${plugin}</plugin>
</xacro:unless>
</hardware>
<joint name="${prefix}joint1">
<param name="initial_position">${initial_positions['joint1']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}joint2">
<param name="initial_position">${initial_positions['joint2']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}joint3">
<param name="initial_position">${initial_positions['joint3']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}joint4">
<param name="initial_position">${initial_positions['joint4']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}joint5">
<param name="initial_position">${initial_positions['joint5']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}joint6">
<param name="initial_position">${initial_positions['joint6']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}joint7">
<param name="initial_position">${initial_positions['joint7']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
</xacro:macro>
<!-- -->
<!-- Macro -->
<!-- -->
<xacro:macro name="ros2_control_panda_gripper" params="
name:=panda_gripper_system
prefix:=panda_
plugin:=fake
command_interface:=effort
initial_positions_file:=${default_initial_positions_file}
mimic_joints:=false
">
<xacro:property name="initial_positions" value="${load_yaml(initial_positions_file)['initial_joint_positions']['panda_gripper']}"/>
<ros2_control name="${name}" type="system">
<hardware>
<xacro:if value="${plugin == 'fake'}">
<plugin>fake_components/GenericSystem</plugin>
</xacro:if>
<xacro:if value="${plugin == 'ign'}">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:if value="${plugin == 'real'}">
<xacro:ERROR_ros2_control_for_real_robot_unimplemented/>
</xacro:if>
<xacro:unless value="${plugin == 'fake' or plugin == 'ign' or plugin == 'real'}">
<plugin>${plugin}</plugin>
</xacro:unless>
</hardware>
<joint name="${prefix}finger_joint1">
<param name="initial_position">${initial_positions['joint1']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}finger_joint2">
<param name="initial_position">${initial_positions['joint2']}</param>
<xacro:if value="${'position' in command_interface}">
<command_interface name="position"/>
</xacro:if>
<xacro:if value="${'velocity' in command_interface}">
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${'effort' in command_interface}">
<command_interface name="effort"/>
</xacro:if>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>