Skip to content
This repository has been archived by the owner on Dec 13, 2024. It is now read-only.

Commit

Permalink
enable controlling gripper through wrist tool comms port
Browse files Browse the repository at this point in the history
  • Loading branch information
schornakj committed Dec 5, 2023
1 parent 42e25a6 commit c9b907d
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 2 deletions.
11 changes: 9 additions & 2 deletions src/picknik_ur_base_config/description/picknik_ur.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,10 @@
<xacro:arg name="headless_mode" default="false" />
<xacro:arg name="robot_ip" default="0.0.0.0" />

<xacro:arg name="tool_usb_port" default="/dev/ttyUSB0" />
<xacro:arg name="use_tool_communication" default="false" />
<xacro:arg name="tool_voltage" default="0" />

<xacro:if value="$(arg has_tool_changer)">
<xacro:property name="camera_adapter_parent" value="tool_changer_tool0" />
</xacro:if>
Expand Down Expand Up @@ -55,7 +59,10 @@
robot_ip="$(arg robot_ip)"
script_filename="$(find ur_robot_driver)/resources/ros_control.urscript"
output_recipe_filename="$(find ur_robot_driver)/resources/rtde_output_recipe.txt"
input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt">
input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt"
use_tool_communication="true"
tool_voltage="$(arg tool_voltage)"
tool_device_name="$(arg tool_usb_port)">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:ur_robot>

Expand All @@ -81,7 +88,7 @@
<xacro:ur_to_robotiq prefix="" connected_to="realsense_camera_adapter_tool0" rotation="0" />

<xacro:robotiq_gripper name="RobotiqGripperHardwareInterface" prefix=""
parent="gripper_mount_link" use_fake_hardware="$(arg use_fake_hardware)" com_port="/dev/ttyUSB0">
parent="gripper_mount_link" use_fake_hardware="$(arg use_fake_hardware)" com_port="$(arg tool_usb_port)">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:robotiq_gripper>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@


from launch import LaunchDescription
from launch.actions import ExecuteProcess
from launch_ros.actions import Node

from moveit_studio_utils_py.launch_common import empty_gen
Expand Down Expand Up @@ -67,9 +68,22 @@ def generate_launch_description():
],
)

# This command is needed when using direct connection to the end effector rather than a
# USB to serial adapter (which is where the default port name of /dev/ttyUSB0 comes from).
start_tool_comms = ExecuteProcess(
name="start_tool_comms",
cmd=[
[
"socat pty,link=/tmp/ttyUR,raw,ignoreeof,waitslave tcp:192.168.1.102:54321"
]
],
shell=True,
)

nodes_to_launch = [
dashboard_client_node,
protective_stop_manager_node,
start_tool_comms,
]

return LaunchDescription(nodes_to_launch)

0 comments on commit c9b907d

Please sign in to comment.