|
1 | 1 | <?xml version="1.0"?>
|
2 | 2 | <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
3 | 3 |
|
4 |
| - <xacro:macro name="ur_ros2_control" params="name prefix |
| 4 | + <xacro:macro name="ur_ros2_control" params=" |
| 5 | + name |
| 6 | + prefix |
5 | 7 | use_fake_hardware:=false fake_sensor_commands:=false
|
| 8 | + sim_gazebo:=false |
| 9 | + sim_ignition:=false |
6 | 10 | headless_mode:=false
|
7 | 11 | initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
|
8 | 12 | use_tool_communication:=false
|
|
12 | 16 |
|
13 | 17 | <ros2_control name="${name}" type="system">
|
14 | 18 | <hardware>
|
| 19 | + <xacro:if value="${sim_gazebo}"> |
| 20 | + <plugin>gazebo_ros2_control/GazeboSystem</plugin> |
| 21 | + </xacro:if> |
| 22 | + <xacro:if value="${sim_ignition}"> |
| 23 | + <plugin>ign_ros2_control/IgnitionSystem</plugin> |
| 24 | + </xacro:if> |
15 | 25 | <xacro:if value="${use_fake_hardware}">
|
16 | 26 | <plugin>fake_components/GenericSystem</plugin>
|
17 | 27 | <param name="fake_sensor_commands">${fake_sensor_commands}</param>
|
18 | 28 | <param name="state_following_offset">0.0</param>
|
19 | 29 | </xacro:if>
|
20 |
| - <xacro:unless value="${use_fake_hardware}"> |
| 30 | + <xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}"> |
21 | 31 | <plugin>ur_robot_driver/URPositionHardwareInterface</plugin>
|
22 | 32 | <param name="robot_ip">${robot_ip}</param>
|
23 | 33 | <param name="script_filename">${script_filename}</param>
|
|
51 | 61 | <param name="min">-3.15</param>
|
52 | 62 | <param name="max">3.15</param>
|
53 | 63 | </command_interface>
|
54 |
| - <state_interface name="position"/> |
| 64 | + <state_interface name="position"> |
| 65 | + <!-- initial position for the FakeSystem and simulation --> |
| 66 | + <param name="initial_value">${initial_positions['shoulder_pan_joint']}</param> |
| 67 | + </state_interface> |
55 | 68 | <state_interface name="velocity"/>
|
56 | 69 | <state_interface name="effort"/>
|
57 |
| - <param name="initial_position">${initial_positions['shoulder_pan_joint']}</param> <!-- initial position for the FakeSystem --> |
58 | 70 | </joint>
|
59 | 71 | <joint name="${prefix}shoulder_lift_joint">
|
60 | 72 | <command_interface name="position">
|
|
65 | 77 | <param name="min">-3.15</param>
|
66 | 78 | <param name="max">3.15</param>
|
67 | 79 | </command_interface>
|
68 |
| - <state_interface name="position"/> |
| 80 | + <state_interface name="position"> |
| 81 | + <!-- initial position for the FakeSystem and simulation --> |
| 82 | + <param name="initial_value">${initial_positions['shoulder_lift_joint']}</param> |
| 83 | + </state_interface> |
69 | 84 | <state_interface name="velocity"/>
|
70 | 85 | <state_interface name="effort"/>
|
71 |
| - <param name="initial_position">${initial_positions['shoulder_lift_joint']}</param> <!-- initial position for the FakeSystem --> |
72 | 86 | </joint>
|
73 | 87 | <joint name="${prefix}elbow_joint">
|
74 | 88 | <command_interface name="position">
|
|
79 | 93 | <param name="min">-3.15</param>
|
80 | 94 | <param name="max">3.15</param>
|
81 | 95 | </command_interface>
|
82 |
| - <state_interface name="position"/> |
| 96 | + <state_interface name="position"> |
| 97 | + <!-- initial position for the FakeSystem and simulation --> |
| 98 | + <param name="initial_value">${initial_positions['elbow_joint']}</param> |
| 99 | + </state_interface> |
83 | 100 | <state_interface name="velocity"/>
|
84 | 101 | <state_interface name="effort"/>
|
85 |
| - <param name="initial_position">${initial_positions['elbow_joint']}</param> <!-- initial position for the FakeSystem --> |
86 | 102 | </joint>
|
87 | 103 | <joint name="${prefix}wrist_1_joint">
|
88 | 104 | <command_interface name="position">
|
|
93 | 109 | <param name="min">-3.2</param>
|
94 | 110 | <param name="max">3.2</param>
|
95 | 111 | </command_interface>
|
96 |
| - <state_interface name="position"/> |
| 112 | + <state_interface name="position"> |
| 113 | + <!-- initial position for the FakeSystem and simulation --> |
| 114 | + <param name="initial_value">${initial_positions['wrist_1_joint']}</param> |
| 115 | + </state_interface> |
97 | 116 | <state_interface name="velocity"/>
|
98 | 117 | <state_interface name="effort"/>
|
99 |
| - <param name="initial_position">${initial_positions['wrist_1_joint']}</param> <!-- initial position for the FakeSystem --> |
100 | 118 | </joint>
|
101 | 119 | <joint name="${prefix}wrist_2_joint">
|
102 | 120 | <command_interface name="position">
|
|
107 | 125 | <param name="min">-3.2</param>
|
108 | 126 | <param name="max">3.2</param>
|
109 | 127 | </command_interface>
|
110 |
| - <state_interface name="position"/> |
| 128 | + <state_interface name="position"> |
| 129 | + <!-- initial position for the FakeSystem and simulation --> |
| 130 | + <param name="initial_value">${initial_positions['wrist_2_joint']}</param> |
| 131 | + </state_interface> |
111 | 132 | <state_interface name="velocity"/>
|
112 | 133 | <state_interface name="effort"/>
|
113 |
| - <param name="initial_position">${initial_positions['wrist_2_joint']}</param> <!-- initial position for the FakeSystem --> |
114 | 134 | </joint>
|
115 | 135 | <joint name="${prefix}wrist_3_joint">
|
116 | 136 | <command_interface name="position">
|
|
121 | 141 | <param name="min">-3.2</param>
|
122 | 142 | <param name="max">3.2</param>
|
123 | 143 | </command_interface>
|
124 |
| - <state_interface name="position"/> |
| 144 | + <state_interface name="position"> |
| 145 | + <!-- initial position for the FakeSystem and simulation --> |
| 146 | + <param name="initial_value">${initial_positions['wrist_3_joint']}</param> |
| 147 | + </state_interface> |
125 | 148 | <state_interface name="velocity"/>
|
126 | 149 | <state_interface name="effort"/>
|
127 |
| - <param name="initial_position">${initial_positions['wrist_3_joint']}</param> <!-- initial position for the FakeSystem --> |
128 | 150 | </joint>
|
129 |
| - <sensor name="tcp_fts_sensor"> |
130 |
| - <state_interface name="force.x"/> |
131 |
| - <state_interface name="force.y"/> |
132 |
| - <state_interface name="force.z"/> |
133 |
| - <state_interface name="torque.x"/> |
134 |
| - <state_interface name="torque.y"/> |
135 |
| - <state_interface name="torque.z"/> |
136 |
| - </sensor> |
137 | 151 |
|
138 |
| - <!-- NOTE The following are joints used only for testing with fake hardware and will change in the future --> |
139 |
| - <joint name="speed_scaling"> |
140 |
| - <state_interface name="speed_scaling_factor"/> |
141 |
| - <param name="initial_speed_scaling_factor">1</param> |
142 |
| - <command_interface name="target_speed_fraction_cmd"/> |
143 |
| - <command_interface name="target_speed_fraction_async_success"/> |
144 |
| - </joint> |
| 152 | + <xacro:unless value="${sim_gazebo or sim_ignition}"> |
| 153 | + <sensor name="tcp_fts_sensor"> |
| 154 | + <state_interface name="force.x"/> |
| 155 | + <state_interface name="force.y"/> |
| 156 | + <state_interface name="force.z"/> |
| 157 | + <state_interface name="torque.x"/> |
| 158 | + <state_interface name="torque.y"/> |
| 159 | + <state_interface name="torque.z"/> |
| 160 | + </sensor> |
145 | 161 |
|
146 |
| - <joint name="gpio"> |
147 |
| - <command_interface name="standard_digital_output_cmd_0"/> |
148 |
| - <command_interface name="standard_digital_output_cmd_1"/> |
149 |
| - <command_interface name="standard_digital_output_cmd_2"/> |
150 |
| - <command_interface name="standard_digital_output_cmd_3"/> |
151 |
| - <command_interface name="standard_digital_output_cmd_4"/> |
152 |
| - <command_interface name="standard_digital_output_cmd_5"/> |
153 |
| - <command_interface name="standard_digital_output_cmd_6"/> |
154 |
| - <command_interface name="standard_digital_output_cmd_7"/> |
155 |
| - <command_interface name="standard_digital_output_cmd_8"/> |
156 |
| - <command_interface name="standard_digital_output_cmd_9"/> |
157 |
| - <command_interface name="standard_digital_output_cmd_10"/> |
158 |
| - <command_interface name="standard_digital_output_cmd_11"/> |
159 |
| - <command_interface name="standard_digital_output_cmd_12"/> |
160 |
| - <command_interface name="standard_digital_output_cmd_13"/> |
161 |
| - <command_interface name="standard_digital_output_cmd_14"/> |
162 |
| - <command_interface name="standard_digital_output_cmd_15"/> |
163 |
| - <command_interface name="standard_digital_output_cmd_16"/> |
164 |
| - <command_interface name="standard_digital_output_cmd_17"/> |
| 162 | + <!-- NOTE The following are joints used only for testing with fake hardware and will change in the future --> |
| 163 | + <joint name="speed_scaling"> |
| 164 | + <state_interface name="speed_scaling_factor"/> |
| 165 | + <param name="initial_speed_scaling_factor">1</param> |
| 166 | + <command_interface name="target_speed_fraction_cmd"/> |
| 167 | + <command_interface name="target_speed_fraction_async_success"/> |
| 168 | + </joint> |
165 | 169 |
|
166 |
| - <command_interface name="standard_analog_output_cmd_0"/> |
167 |
| - <command_interface name="standard_analog_output_cmd_1"/> |
| 170 | + <joint name="gpio"> |
| 171 | + <command_interface name="standard_digital_output_cmd_0"/> |
| 172 | + <command_interface name="standard_digital_output_cmd_1"/> |
| 173 | + <command_interface name="standard_digital_output_cmd_2"/> |
| 174 | + <command_interface name="standard_digital_output_cmd_3"/> |
| 175 | + <command_interface name="standard_digital_output_cmd_4"/> |
| 176 | + <command_interface name="standard_digital_output_cmd_5"/> |
| 177 | + <command_interface name="standard_digital_output_cmd_6"/> |
| 178 | + <command_interface name="standard_digital_output_cmd_7"/> |
| 179 | + <command_interface name="standard_digital_output_cmd_8"/> |
| 180 | + <command_interface name="standard_digital_output_cmd_9"/> |
| 181 | + <command_interface name="standard_digital_output_cmd_10"/> |
| 182 | + <command_interface name="standard_digital_output_cmd_11"/> |
| 183 | + <command_interface name="standard_digital_output_cmd_12"/> |
| 184 | + <command_interface name="standard_digital_output_cmd_13"/> |
| 185 | + <command_interface name="standard_digital_output_cmd_14"/> |
| 186 | + <command_interface name="standard_digital_output_cmd_15"/> |
| 187 | + <command_interface name="standard_digital_output_cmd_16"/> |
| 188 | + <command_interface name="standard_digital_output_cmd_17"/> |
168 | 189 |
|
169 |
| - <command_interface name="io_async_success"/> |
| 190 | + <command_interface name="standard_analog_output_cmd_0"/> |
| 191 | + <command_interface name="standard_analog_output_cmd_1"/> |
170 | 192 |
|
171 |
| - <state_interface name="digital_output_0"/> |
172 |
| - <state_interface name="digital_output_1"/> |
173 |
| - <state_interface name="digital_output_2"/> |
174 |
| - <state_interface name="digital_output_3"/> |
175 |
| - <state_interface name="digital_output_4"/> |
176 |
| - <state_interface name="digital_output_5"/> |
177 |
| - <state_interface name="digital_output_6"/> |
178 |
| - <state_interface name="digital_output_7"/> |
179 |
| - <state_interface name="digital_output_8"/> |
180 |
| - <state_interface name="digital_output_9"/> |
181 |
| - <state_interface name="digital_output_10"/> |
182 |
| - <state_interface name="digital_output_11"/> |
183 |
| - <state_interface name="digital_output_12"/> |
184 |
| - <state_interface name="digital_output_13"/> |
185 |
| - <state_interface name="digital_output_14"/> |
186 |
| - <state_interface name="digital_output_15"/> |
187 |
| - <state_interface name="digital_output_16"/> |
188 |
| - <state_interface name="digital_output_17"/> |
| 193 | + <command_interface name="io_async_success"/> |
189 | 194 |
|
190 |
| - <state_interface name="digital_input_0"/> |
191 |
| - <state_interface name="digital_input_1"/> |
192 |
| - <state_interface name="digital_input_2"/> |
193 |
| - <state_interface name="digital_input_3"/> |
194 |
| - <state_interface name="digital_input_4"/> |
195 |
| - <state_interface name="digital_input_5"/> |
196 |
| - <state_interface name="digital_input_6"/> |
197 |
| - <state_interface name="digital_input_7"/> |
198 |
| - <state_interface name="digital_input_8"/> |
199 |
| - <state_interface name="digital_input_9"/> |
200 |
| - <state_interface name="digital_input_10"/> |
201 |
| - <state_interface name="digital_input_11"/> |
202 |
| - <state_interface name="digital_input_12"/> |
203 |
| - <state_interface name="digital_input_13"/> |
204 |
| - <state_interface name="digital_input_14"/> |
205 |
| - <state_interface name="digital_input_15"/> |
206 |
| - <state_interface name="digital_input_16"/> |
207 |
| - <state_interface name="digital_input_17"/> |
| 195 | + <state_interface name="digital_output_0"/> |
| 196 | + <state_interface name="digital_output_1"/> |
| 197 | + <state_interface name="digital_output_2"/> |
| 198 | + <state_interface name="digital_output_3"/> |
| 199 | + <state_interface name="digital_output_4"/> |
| 200 | + <state_interface name="digital_output_5"/> |
| 201 | + <state_interface name="digital_output_6"/> |
| 202 | + <state_interface name="digital_output_7"/> |
| 203 | + <state_interface name="digital_output_8"/> |
| 204 | + <state_interface name="digital_output_9"/> |
| 205 | + <state_interface name="digital_output_10"/> |
| 206 | + <state_interface name="digital_output_11"/> |
| 207 | + <state_interface name="digital_output_12"/> |
| 208 | + <state_interface name="digital_output_13"/> |
| 209 | + <state_interface name="digital_output_14"/> |
| 210 | + <state_interface name="digital_output_15"/> |
| 211 | + <state_interface name="digital_output_16"/> |
| 212 | + <state_interface name="digital_output_17"/> |
208 | 213 |
|
209 |
| - <state_interface name="standard_analog_output_0"/> |
210 |
| - <state_interface name="standard_analog_output_1"/> |
| 214 | + <state_interface name="digital_input_0"/> |
| 215 | + <state_interface name="digital_input_1"/> |
| 216 | + <state_interface name="digital_input_2"/> |
| 217 | + <state_interface name="digital_input_3"/> |
| 218 | + <state_interface name="digital_input_4"/> |
| 219 | + <state_interface name="digital_input_5"/> |
| 220 | + <state_interface name="digital_input_6"/> |
| 221 | + <state_interface name="digital_input_7"/> |
| 222 | + <state_interface name="digital_input_8"/> |
| 223 | + <state_interface name="digital_input_9"/> |
| 224 | + <state_interface name="digital_input_10"/> |
| 225 | + <state_interface name="digital_input_11"/> |
| 226 | + <state_interface name="digital_input_12"/> |
| 227 | + <state_interface name="digital_input_13"/> |
| 228 | + <state_interface name="digital_input_14"/> |
| 229 | + <state_interface name="digital_input_15"/> |
| 230 | + <state_interface name="digital_input_16"/> |
| 231 | + <state_interface name="digital_input_17"/> |
211 | 232 |
|
212 |
| - <state_interface name="standard_analog_input_0"/> |
213 |
| - <state_interface name="standard_analog_input_1"/> |
| 233 | + <state_interface name="standard_analog_output_0"/> |
| 234 | + <state_interface name="standard_analog_output_1"/> |
214 | 235 |
|
215 |
| - <state_interface name="analog_io_type_0"/> |
216 |
| - <state_interface name="analog_io_type_1"/> |
217 |
| - <state_interface name="analog_io_type_2"/> |
218 |
| - <state_interface name="analog_io_type_3"/> |
| 236 | + <state_interface name="standard_analog_input_0"/> |
| 237 | + <state_interface name="standard_analog_input_1"/> |
219 | 238 |
|
220 |
| - <state_interface name="tool_mode"/> |
221 |
| - <state_interface name="tool_output_voltage"/> |
222 |
| - <state_interface name="tool_output_current"/> |
223 |
| - <state_interface name="tool_temperature"/> |
| 239 | + <state_interface name="analog_io_type_0"/> |
| 240 | + <state_interface name="analog_io_type_1"/> |
| 241 | + <state_interface name="analog_io_type_2"/> |
| 242 | + <state_interface name="analog_io_type_3"/> |
224 | 243 |
|
225 |
| - <state_interface name="tool_analog_input_0"/> |
226 |
| - <state_interface name="tool_analog_input_1"/> |
| 244 | + <state_interface name="tool_mode"/> |
| 245 | + <state_interface name="tool_output_voltage"/> |
| 246 | + <state_interface name="tool_output_current"/> |
| 247 | + <state_interface name="tool_temperature"/> |
227 | 248 |
|
228 |
| - <state_interface name="tool_analog_input_type_0"/> |
229 |
| - <state_interface name="tool_analog_input_type_1"/> |
| 249 | + <state_interface name="tool_analog_input_0"/> |
| 250 | + <state_interface name="tool_analog_input_1"/> |
230 | 251 |
|
231 |
| - <state_interface name="robot_mode"/> |
232 |
| - <state_interface name="robot_status_bit_0"/> |
233 |
| - <state_interface name="robot_status_bit_1"/> |
234 |
| - <state_interface name="robot_status_bit_2"/> |
235 |
| - <state_interface name="robot_status_bit_3"/> |
| 252 | + <state_interface name="tool_analog_input_type_0"/> |
| 253 | + <state_interface name="tool_analog_input_type_1"/> |
236 | 254 |
|
237 |
| - <state_interface name="safety_mode"/> |
238 |
| - <state_interface name="safety_status_bit_0"/> |
239 |
| - <state_interface name="safety_status_bit_1"/> |
240 |
| - <state_interface name="safety_status_bit_2"/> |
241 |
| - <state_interface name="safety_status_bit_3"/> |
242 |
| - <state_interface name="safety_status_bit_4"/> |
243 |
| - <state_interface name="safety_status_bit_5"/> |
244 |
| - <state_interface name="safety_status_bit_6"/> |
245 |
| - <state_interface name="safety_status_bit_7"/> |
246 |
| - <state_interface name="safety_status_bit_8"/> |
247 |
| - <state_interface name="safety_status_bit_9"/> |
248 |
| - <state_interface name="safety_status_bit_10"/> |
249 |
| - </joint> |
| 255 | + <state_interface name="robot_mode"/> |
| 256 | + <state_interface name="robot_status_bit_0"/> |
| 257 | + <state_interface name="robot_status_bit_1"/> |
| 258 | + <state_interface name="robot_status_bit_2"/> |
| 259 | + <state_interface name="robot_status_bit_3"/> |
250 | 260 |
|
251 |
| - <joint name="resend_robot_program"> |
252 |
| - <command_interface name="resend_robot_program_cmd"/> |
253 |
| - <command_interface name="resend_robot_program_async_success"/> |
254 |
| - </joint> |
| 261 | + <state_interface name="safety_mode"/> |
| 262 | + <state_interface name="safety_status_bit_0"/> |
| 263 | + <state_interface name="safety_status_bit_1"/> |
| 264 | + <state_interface name="safety_status_bit_2"/> |
| 265 | + <state_interface name="safety_status_bit_3"/> |
| 266 | + <state_interface name="safety_status_bit_4"/> |
| 267 | + <state_interface name="safety_status_bit_5"/> |
| 268 | + <state_interface name="safety_status_bit_6"/> |
| 269 | + <state_interface name="safety_status_bit_7"/> |
| 270 | + <state_interface name="safety_status_bit_8"/> |
| 271 | + <state_interface name="safety_status_bit_9"/> |
| 272 | + <state_interface name="safety_status_bit_10"/> |
| 273 | + </joint> |
255 | 274 |
|
256 |
| - <joint name="system_interface"> |
257 |
| - <state_interface name="initialized"/> |
258 |
| - </joint> |
| 275 | + <joint name="resend_robot_program"> |
| 276 | + <command_interface name="resend_robot_program_cmd"/> |
| 277 | + <command_interface name="resend_robot_program_async_success"/> |
| 278 | + </joint> |
| 279 | + |
| 280 | + <joint name="system_interface"> |
| 281 | + <state_interface name="initialized"/> |
| 282 | + </joint> |
| 283 | + |
| 284 | + </xacro:unless> |
259 | 285 |
|
260 | 286 | </ros2_control>
|
| 287 | + |
261 | 288 | </xacro:macro>
|
262 | 289 |
|
263 | 290 | </robot>
|
0 commit comments