|
228 | 228 | <gpio name="${tf_prefix}system_interface"> |
229 | 229 | <state_interface name="initialized"/> |
230 | 230 | </gpio> |
| 231 | + |
| 232 | + <gpio name="${tf_prefix}force_mode"> |
| 233 | + <command_interface name="task_frame_x"/> |
| 234 | + <command_interface name="task_frame_y"/> |
| 235 | + <command_interface name="task_frame_z"/> |
| 236 | + <command_interface name="task_frame_rx"/> |
| 237 | + <command_interface name="task_frame_ry"/> |
| 238 | + <command_interface name="task_frame_rz"/> |
| 239 | + <command_interface name="selection_vector_x"/> |
| 240 | + <command_interface name="selection_vector_y"/> |
| 241 | + <command_interface name="selection_vector_z"/> |
| 242 | + <command_interface name="selection_vector_rx"/> |
| 243 | + <command_interface name="selection_vector_ry"/> |
| 244 | + <command_interface name="selection_vector_rz"/> |
| 245 | + <command_interface name="wrench_x"/> |
| 246 | + <command_interface name="wrench_y"/> |
| 247 | + <command_interface name="wrench_z"/> |
| 248 | + <command_interface name="wrench_rx"/> |
| 249 | + <command_interface name="wrench_ry"/> |
| 250 | + <command_interface name="wrench_rz"/> |
| 251 | + <command_interface name="limits_x"/> |
| 252 | + <command_interface name="limits_y"/> |
| 253 | + <command_interface name="limits_z"/> |
| 254 | + <command_interface name="limits_rx"/> |
| 255 | + <command_interface name="limits_ry"/> |
| 256 | + <command_interface name="limits_rz"/> |
| 257 | + <command_interface name="type"/> |
| 258 | + <command_interface name="damping"/> |
| 259 | + <command_interface name="gain_scaling"/> |
| 260 | + <command_interface name="disable_cmd"/> |
| 261 | + <command_interface name="force_mode_async_success"/> |
| 262 | + </gpio> |
231 | 263 | </ros2_control> |
232 | 264 | </xacro:macro> |
233 | 265 | </robot> |
0 commit comments