|
336 | 336 | <command_interface name="zero_ftsensor_async_success"/> |
337 | 337 | </gpio> |
338 | 338 |
|
| 339 | + <gpio name="${tf_prefix}force_mode"> |
| 340 | + <command_interface name="task_frame_x"/> |
| 341 | + <command_interface name="task_frame_y"/> |
| 342 | + <command_interface name="task_frame_z"/> |
| 343 | + <command_interface name="task_frame_rx"/> |
| 344 | + <command_interface name="task_frame_ry"/> |
| 345 | + <command_interface name="task_frame_rz"/> |
| 346 | + <command_interface name="selection_vector_x"/> |
| 347 | + <command_interface name="selection_vector_y"/> |
| 348 | + <command_interface name="selection_vector_z"/> |
| 349 | + <command_interface name="selection_vector_rx"/> |
| 350 | + <command_interface name="selection_vector_ry"/> |
| 351 | + <command_interface name="selection_vector_rz"/> |
| 352 | + <command_interface name="wrench_x"/> |
| 353 | + <command_interface name="wrench_y"/> |
| 354 | + <command_interface name="wrench_z"/> |
| 355 | + <command_interface name="wrench_rx"/> |
| 356 | + <command_interface name="wrench_ry"/> |
| 357 | + <command_interface name="wrench_rz"/> |
| 358 | + <command_interface name="limits_x"/> |
| 359 | + <command_interface name="limits_y"/> |
| 360 | + <command_interface name="limits_z"/> |
| 361 | + <command_interface name="limits_rx"/> |
| 362 | + <command_interface name="limits_ry"/> |
| 363 | + <command_interface name="limits_rz"/> |
| 364 | + <command_interface name="type"/> |
| 365 | + <command_interface name="disable_cmd"/> |
| 366 | + <command_interface name="force_mode_async_success"/> |
| 367 | + <command_interface name="damping"/> |
| 368 | + <command_interface name="gain_scaling"/> |
| 369 | + </gpio> |
| 370 | + |
339 | 371 | <gpio name="${tf_prefix}system_interface"> |
340 | 372 | <state_interface name="initialized"/> |
341 | 373 | </gpio> |
|
0 commit comments