Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rest node upgrades #7

Merged
merged 28 commits into from
Jun 17, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
df1f746
Added more imports
Dozgulbas Jun 7, 2024
bf90d41
Clean up
Dozgulbas Jun 8, 2024
d80a260
Adding Pick tool action
Dozgulbas Jun 8, 2024
4825ee2
Fixing the optional argument errors
Dozgulbas Jun 10, 2024
93b93fa
Added pick tool action
Dozgulbas Jun 10, 2024
87d36a3
Adding new action funtions
Dozgulbas Jun 11, 2024
228dd3f
Added pick and flip object
Dozgulbas Jun 11, 2024
9de7b29
Adding docstrings
Dozgulbas Jun 11, 2024
cb4293d
Adding docstrings
Dozgulbas Jun 11, 2024
f1d8e8d
Increased line lenght
Dozgulbas Jun 11, 2024
c975dec
Added all the actions into rest node
Dozgulbas Jun 11, 2024
40c3999
Increased line lenght
Dozgulbas Jun 11, 2024
5d3fae2
Removed old rest node
Dozgulbas Jun 11, 2024
6985fe3
Fixing state response error
Dozgulbas Jun 11, 2024
485fa9e
Working on adding a simulation mode
Dozgulbas Jun 11, 2024
a7c8cfe
Minor changes
Dozgulbas Jun 11, 2024
1dc240b
Working on replacing the WEI data classes
Dozgulbas Jun 12, 2024
356497c
Working on replacing the WEI data classes
Dozgulbas Jun 12, 2024
bfacd53
Renaming
Dozgulbas Jun 12, 2024
d8c2234
fixing unittests errors
Dozgulbas Jun 12, 2024
77fe2b7
Tryingg to fix unit test bugs
Dozgulbas Jun 13, 2024
dff5e5f
Minor updates
Dozgulbas Jun 13, 2024
c3b867a
Fixing arg errors
Dozgulbas Jun 13, 2024
6c82eb8
Fixing arg errors
Dozgulbas Jun 13, 2024
3b2993a
IP updated
Dozgulbas Jun 14, 2024
ec15804
Fix tests; cleanup
LuckierDodge Jun 14, 2024
e90031f
Pytest passing
Dozgulbas Jun 14, 2024
98ae529
PR Review
LuckierDodge Jun 17, 2024
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 0 additions & 8 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,6 @@

init: # Do the initial configuration of the project
@test -e .env || cp example.env .env
ifeq ($(shell uname),Darwin)
@sed -i '' 's|^PROJECT_PATH=.*|PROJECT_PATH=$(shell pwd | sed 's/\//\\\//g')|' .env
else
@sed -i 's/^PROJECT_PATH=.*/PROJECT_PATH=$(shell pwd | sed 's/\//\\\//g')/' .env
endif

.env: init

Expand All @@ -24,6 +19,3 @@ test: init .env paths # Runs all the tests
@docker compose -f wei.compose.yaml --env-file .env up --build -d
@docker compose -f wei.compose.yaml --env-file .env exec ur_module pytest -p no:cacheprovider ur_module
@docker compose -f wei.compose.yaml --env-file .env down

clean:
@rm .env
3 changes: 1 addition & 2 deletions example.env
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
# Note: all paths are relative to the docker compose file
UR_IP="164.54.116.129"
PROJECT_PATH=
WEI_DATA_DIR=~/.wei
WORKCELL_FILENAME=test_workcell.yaml
WORKCELLS_DIR=${PROJECT_PATH}/tests/workcell_defs
WORKCELLS_DIR=./tests/workcell_defs
IMAGE=ghcr.io/ad-sdl/ur_module
REDIS_DIR=~/.wei/redis
2 changes: 1 addition & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ exclude = [
]

# Same as Black.
line-length = 88
line-length = 120
indent-width = 4

# Assume Python 3.8
Expand Down
75 changes: 27 additions & 48 deletions src/ur_driver/ur.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,14 +9,10 @@
from urx import Robot

from ur_driver.ur_dashboard import UR_DASHBOARD
from ur_driver.ur_tools.gripper_controller import (
FingerGripperController,
)
from ur_driver.ur_tools.gripper_controller import FingerGripperController
from ur_driver.ur_tools.ot_pipette_controller import OTPipetteController
from ur_driver.ur_tools.screwdriver_controller import ScrewdriverController
from ur_driver.ur_tools.tricontinent_pipette_controller import (
TricontinentPipetteController,
)
from ur_driver.ur_tools.tricontinent_pipette_controller import TricontinentPipetteController
from ur_driver.ur_tools.wm_tool_changer_controller import WMToolChangerController


Expand Down Expand Up @@ -75,10 +71,6 @@ def __init__(self, hostname: str = None, PORT: int = 29999):

self.hostname = hostname
self.PORT = PORT
self.ur_dashboard = UR_DASHBOARD(hostname=self.hostname, PORT=self.PORT)
self.ur = Connection(hostname=self.hostname)
self.ur_connection = self.ur.connection
self.ur_connection.set_tcp((0, 0, 0, 0, 0, 0))
self.acceleration = 0.5
self.velocity = 0.5
self.speed_ms = 0.750
Expand All @@ -88,18 +80,25 @@ def __init__(self, hostname: str = None, PORT: int = 29999):
self.blend_radius_m = 0.001
self.ref_frame = [0, 0, 0, 0, 0, 0]
self.robot_current_joint_angles = None

# if not self.hostname == "127.0.0.1":
self.ur_dashboard = UR_DASHBOARD(hostname=self.hostname, PORT=self.PORT)
self.ur = Connection(hostname=self.hostname)
self.ur_connection = self.ur.connection
self.ur_connection.set_tcp((0, 0, 0, 0, 0, 0))
self.get_movement_state()
# TODO: get the information of what is the current tool attached to UR. Run a senity check at the beginning to findout if a tool is connected
# else:
# TODO: Use simulation mode for local IP

# TODO: get the information of what is the current tool attached to UR. Run a sanity check at the beginning to find out if a tool is connected

def get_movement_state(self) -> str:
"""Gets robot movement status by checking robot joint values.
Return (str) READY if robot is not moving
BUSY if robot is moving
"""
current_location = self.ur_connection.getj()
current_location = [
"%.2f" % value for value in current_location
] # rounding to 3 digits
current_location = ["%.2f" % value for value in current_location] # rounding to 3 digits
# print(current_location)
if self.robot_current_joint_angles == current_location:
movement_state = "READY"
Expand Down Expand Up @@ -223,16 +222,12 @@ def gripper_transfer(
"""

if not source or not target:
raise Exception(
"Please provide both the source and target loactions to make a transfer"
)
raise Exception("Please provide both the source and target locations to make a transfer")

self.home(home)

try:
gripper_controller = FingerGripperController(
hostname=self.hostname, ur=self.ur_connection
)
gripper_controller = FingerGripperController(hostname=self.hostname, ur=self.ur_connection)
gripper_controller.connect_gripper()

if gripper_open:
Expand Down Expand Up @@ -276,7 +271,7 @@ def gripper_screw_transfer(
target(list): Target location
screwdriver_loc (list): Location of the screwdriving bit
screw_loc (list): Location where the screwdriving will be performed
screw_time (float): Screwdriving durition
screw_time (float): Screwdriving duration
gripper_open (int): Gripper max open value (0-255)
gripper_close (int): Gripper min close value (0-255)

Expand All @@ -285,9 +280,7 @@ def gripper_screw_transfer(
self.home(home)

try:
gripper_controller = FingerGripperController(
hostname=self.hostname, ur=self.ur_connection
)
gripper_controller = FingerGripperController(hostname=self.hostname, ur=self.ur_connection)
gripper_controller.connect_gripper()

if gripper_open:
Expand Down Expand Up @@ -365,9 +358,7 @@ def remove_cap(
self.home(home)

try:
gripper_controller = FingerGripperController(
hostname=self.hostname, ur=self.ur_connection
)
gripper_controller = FingerGripperController(hostname=self.hostname, ur=self.ur_connection)
gripper_controller.connect_gripper()
if gripper_open:
gripper_controller.gripper_open = gripper_open
Expand Down Expand Up @@ -419,9 +410,7 @@ def place_cap(
self.home(home)

try:
gripper_controller = FingerGripperController(
hostname=self.hostname, ur=self.ur_connection
)
gripper_controller = FingerGripperController(hostname=self.hostname, ur=self.ur_connection)
gripper_controller.connect_gripper()
if gripper_open:
gripper_controller.gripper_open = gripper_open
Expand Down Expand Up @@ -476,9 +465,7 @@ def pick_and_flip_object(
self.home(home)

try:
gripper_controller = FingerGripperController(
hostname=self.hostname, ur=self.ur_connection
)
gripper_controller = FingerGripperController(hostname=self.hostname, ur=self.ur_connection)
gripper_controller.connect_gripper()

if gripper_open:
Expand Down Expand Up @@ -572,9 +559,7 @@ def pipette_transfer(
volume (int): Pipette transfer volume. Unit number of steps. Each step is 1 mL
"""
if not tip_loc or not source:
raise Exception(
"Please provide both the source and target loactions to make a transfer"
)
raise Exception("Please provide both the source and target loactions to make a transfer")

try:
pipette = TricontinentPipetteController(
Expand All @@ -583,9 +568,7 @@ def pipette_transfer(
pipette.connect_pipette()
pipette.pick_tip(tip_loc=tip_loc)
self.home(home)
pipette.transfer_sample(
home=home, sample_aspirate=source, sample_dispense=target, vol=volume
)
pipette.transfer_sample(home=home, sample_aspirate=source, sample_dispense=target, vol=volume)
pipette.eject_tip(eject_tip_loc=tip_trash, approach_axis="y")
pipette.disconnect_pipette()
print("Disconnecting from the pipette")
Expand All @@ -609,9 +592,7 @@ def run_droplet(
droplet_loc (list): Location where the droplet will be hung
tip_trash (list): Pipette tip trash location
"""
pipette = OTPipetteController(
ur_connection=self.ur_connection, IP=self.hostname
)
pipette = OTPipetteController(ur_connection=self.ur_connection, IP=self.hostname)
pipette.connect_pipette()

self.home(home)
Expand All @@ -638,9 +619,7 @@ def run_urp_program(self, transfer_file_path: str = None, program_name: str = No
ur_program_path = "/programs/" + program_name

if transfer_file_path:
self.ur_dashboard.transfer_program(
local_path=transfer_file_path, remote_path=ur_program_path
)
self.ur_dashboard.transfer_program(local_path=transfer_file_path, remote_path=ur_program_path)
sleep(2)

self.ur_dashboard.load_program(program_path=ur_program_path)
Expand Down Expand Up @@ -674,8 +653,8 @@ def run_urp_program(self, transfer_file_path: str = None, program_name: str = No
if __name__ == "__main__":
"""Tests"""

pos1 = [-0.22575, -0.65792, 0.39271, 2.216, 2.196, -0.043]
pos2 = [0.22575, -0.65792, 0.39271, 2.216, 2.196, -0.043]
# pos1 = [-0.22575, -0.65792, 0.39271, 2.216, 2.196, -0.043]
# pos2 = [0.22575, -0.65792, 0.39271, 2.216, 2.196, -0.043]
robot3 = UR(hostname="164.54.116.129") # UR3
robot5 = UR(hostname="164.54.116.109") # UR5

Expand Down Expand Up @@ -880,5 +859,5 @@ def run_urp_program(self, transfer_file_path: str = None, program_name: str = No
# robot5.gripper_transfer(home = ur5_home, source = ur5_cell_holder, target = ur5_measurement_unit, source_approach_axis="z", target_approach_axis="z",source_approach_distance=0.15, target_approach_distance=0.15, gripper_open = 190, gripper_close = 240)
# robot5.place_tool(home= ur5_home,tool_loc=ur5_handE)

robot3.ur.disconnect_ur()
# robot3.ur.disconnect_ur()
robot5.ur.disconnect_ur()
52 changes: 21 additions & 31 deletions src/ur_driver/ur_dashboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,17 @@

class UR_DASHBOARD:
"""
This is a python interface to communicate the UR Dashboard server.
UR can be controlled from remote by sending simple commands to the GUI over a TCP/IP socket.
This is a python interface to communicate with the UR Dashboard server.
The UR can be controlled remotely by sending simple commands to the GUI over a TCP/IP socket.
The server is running on port 29999 on the robots IP address.
Each command should be terminated by a `\n` also called a newline.
"""

def __init__(self, hostname: str = "146.137.240.38", PORT: int = 29999) -> None:
def __init__(
self,
hostname: str = "146.137.240.38",
PORT: int = 29999,
) -> None:
"""Constructor for the UR dashboard class.
:param hostname: Hostname or ip.
:param port: Port.
Expand All @@ -32,15 +36,14 @@ def __init__(self, hostname: str = "146.137.240.38", PORT: int = 29999) -> None:
self.connect()
if self.connection_error:
raise Exception("Can't connect to dashboard")
sleep(3)
self.initialize()

def connect(self) -> None:
"""Create a socket"""
try:
self.connection = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.connection.settimeout(
5
) # Socket will wait 5 seconds till it recieves the response
self.connection.settimeout(5) # Socket will wait 5 seconds till it receives the response
self.connection.connect((self.hostname, self.port))

except socket.error as err:
Expand All @@ -52,7 +55,11 @@ def disconnect(self) -> None:
"""Close the socket"""
self.connection.close()

def send_command(self, command: str = None, response_delay: float = 0.1) -> str:
def send_command(
self,
command: str = None,
response_delay: float = 0.1,
) -> str:
"""Constructs a command to send over the Dashboard socket
Args
command (str): Robot command.
Expand Down Expand Up @@ -293,7 +300,12 @@ def transfer_program(
hostname=self.hostname,
username=user_name,
password=user_password,
disabled_algorithms={"pubkeys": ["rsa-sha2-256", "rsa-sha2-512"]},
disabled_algorithms={
"pubkeys": [
"rsa-sha2-256",
"rsa-sha2-512",
]
},
)
with SCPClient(ssh_client.get_transport()) as scp:
scp.put(local_path, remote_path)
Expand All @@ -305,12 +317,7 @@ def transfer_program(
print("SCP error: " + scp_err)

else:
print(
"UR program "
+ local_path
+ " is transferred to UR onboard "
+ remote_path
)
print("UR program " + local_path + " is transferred to UR onboard " + remote_path)

finally:
scp.close()
Expand Down Expand Up @@ -394,20 +401,3 @@ def stop_program(self) -> str:
# robot.transfer_program("/home/rpl/test.urp", "/programs/katerina.urp")
# robot.load_program("/programs/katerina.urp")
# robot.run_program()

"""
Bug: Output error message breaks the client state check, causing the client to retry connection

[ur5_client-1] [INFO] [1685573134.289546521] [ur5_client.UR5_Client_Node]: {'program_name': 'chemspeed2tecan'}
[ur5_client-1] [INFO] [1685573134.290071438] [ur5_client.UR5_Client_Node]: None
[ur5_client-1] [INFO] [1685573134.290490743] [ur5_client.UR5_Client_Node]: chemspeed2tecan
[ur5_client-1] << NONE
[ur5_client-1] File not found: /programs/chemspeed2tecan
[ur5_client-1] << Safetystatus: NORMAL
[ur5_client-1] << Robotmode: RUNNING
[ur5_client-1] ['Robotmode:', 'RUNNING']
[ur5_client-1] << true
[ur5_client-1] [ERROR] [1685573134.745633959] [ur5_client.UR5_Client_Node]: list index out of range
[ur5_client-1] [ERROR] [1685573134.746134932] [ur5_client.UR5_Client_Node]: State: ERROR
[ur5_client-1] [ERROR] [1685573134.746477735] [ur5_client.UR5_Client_Node]: Robot_Mode: RUNNING Safety_Status: RUNNING
"""
10 changes: 8 additions & 2 deletions src/ur_driver/ur_tools/ati_tool_changer_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,10 @@ def lock_tool_changer(self):
print("Locking the tool changer...")
self.tool_changer.put(1)
except Exception as err:
print("Error accured while locking the tool changer: ", err)
print(
"Error accured while locking the tool changer: ",
err,
)

def unlock_tool_changer(self):
"""
Expand All @@ -73,4 +76,7 @@ def unlock_tool_changer(self):
print("Unlocking the tool changer...")
self.tool_changer.put(0)
except Exception as err:
print("Error accured while unlocking the tool changer: ", err)
print(
"Error accured while unlocking the tool changer: ",
err,
)
Loading
Loading