|
288 | 288 | <command_interface name="zero_ftsensor_async_success"/> |
289 | 289 | </gpio> |
290 | 290 |
|
| 291 | + <gpio name="${tf_prefix}freedrive_mode"> |
| 292 | + <command_interface name="async_success"/> |
| 293 | + <command_interface name="enable"/> |
| 294 | + <command_interface name="abort"/> |
| 295 | + </gpio> |
| 296 | + |
291 | 297 | <gpio name="${tf_prefix}system_interface"> |
292 | 298 | <state_interface name="initialized"/> |
293 | 299 | </gpio> |
294 | 300 |
|
| 301 | + <gpio name="${tf_prefix}force_mode"> |
| 302 | + <command_interface name="task_frame_x"/> |
| 303 | + <command_interface name="task_frame_y"/> |
| 304 | + <command_interface name="task_frame_z"/> |
| 305 | + <command_interface name="task_frame_rx"/> |
| 306 | + <command_interface name="task_frame_ry"/> |
| 307 | + <command_interface name="task_frame_rz"/> |
| 308 | + <command_interface name="selection_vector_x"/> |
| 309 | + <command_interface name="selection_vector_y"/> |
| 310 | + <command_interface name="selection_vector_z"/> |
| 311 | + <command_interface name="selection_vector_rx"/> |
| 312 | + <command_interface name="selection_vector_ry"/> |
| 313 | + <command_interface name="selection_vector_rz"/> |
| 314 | + <command_interface name="wrench_x"/> |
| 315 | + <command_interface name="wrench_y"/> |
| 316 | + <command_interface name="wrench_z"/> |
| 317 | + <command_interface name="wrench_rx"/> |
| 318 | + <command_interface name="wrench_ry"/> |
| 319 | + <command_interface name="wrench_rz"/> |
| 320 | + <command_interface name="limits_x"/> |
| 321 | + <command_interface name="limits_y"/> |
| 322 | + <command_interface name="limits_z"/> |
| 323 | + <command_interface name="limits_rx"/> |
| 324 | + <command_interface name="limits_ry"/> |
| 325 | + <command_interface name="limits_rz"/> |
| 326 | + <command_interface name="type"/> |
| 327 | + <command_interface name="damping"/> |
| 328 | + <command_interface name="gain_scaling"/> |
| 329 | + <command_interface name="disable_cmd"/> |
| 330 | + <command_interface name="force_mode_async_success"/> |
| 331 | + </gpio> |
| 332 | + |
| 333 | + <gpio name="${tf_prefix}trajectory_passthrough"> |
| 334 | + <command_interface name="setpoint_positions_0"/> |
| 335 | + <command_interface name="setpoint_positions_1"/> |
| 336 | + <command_interface name="setpoint_positions_2"/> |
| 337 | + <command_interface name="setpoint_positions_3"/> |
| 338 | + <command_interface name="setpoint_positions_4"/> |
| 339 | + <command_interface name="setpoint_positions_5"/> |
| 340 | + <command_interface name="setpoint_velocities_0"/> |
| 341 | + <command_interface name="setpoint_velocities_1"/> |
| 342 | + <command_interface name="setpoint_velocities_2"/> |
| 343 | + <command_interface name="setpoint_velocities_3"/> |
| 344 | + <command_interface name="setpoint_velocities_4"/> |
| 345 | + <command_interface name="setpoint_velocities_5"/> |
| 346 | + <command_interface name="setpoint_accelerations_0"/> |
| 347 | + <command_interface name="setpoint_accelerations_1"/> |
| 348 | + <command_interface name="setpoint_accelerations_2"/> |
| 349 | + <command_interface name="setpoint_accelerations_3"/> |
| 350 | + <command_interface name="setpoint_accelerations_4"/> |
| 351 | + <command_interface name="setpoint_accelerations_5"/> |
| 352 | + <command_interface name="transfer_state"/> |
| 353 | + <command_interface name="time_from_start"/> |
| 354 | + <command_interface name="abort"/> |
| 355 | + </gpio> |
| 356 | + |
295 | 357 | <gpio name="${tf_prefix}get_robot_software_version"> |
296 | 358 | <state_interface name="get_version_major"/> |
297 | 359 | <state_interface name="get_version_minor"/> |
|
0 commit comments