From 87daaf325f13bc980515c8e615c31baf48ca8fb6 Mon Sep 17 00:00:00 2001 From: m-guberina <gubi.guberina@gmail.com> Date: Tue, 4 Feb 2025 17:43:50 +0100 Subject: [PATCH] no servers on smc - all wherever ros1 is. also made joint file for both publishing and subscribing so you only need to start ros1_protobuf_bridge.py --- Dockerfile_no_conda | 86 +++++++++ .../graz/cartesian_pose_command_server.py | 14 +- python/examples/graz/clik_client.py | 19 +- python/examples/graz/joint_copier_client.py | 8 +- .../examples/graz/point_impedance_server.py | 4 +- python/examples/graz/protobuf_ros1_bridge.py | 171 ++++++++++++++++++ python/examples/graz/protobuf_to_ros1.py | 64 +++---- python/examples/graz/ros1_to_protobuf.py | 37 +++- .../__pycache__/__init__.cpython-311.pyc | Bin 488 -> 488 bytes .../__pycache__/managers.cpython-311.pyc | Bin 61250 -> 61250 bytes .../clik/__pycache__/__init__.cpython-311.pyc | Bin 248 -> 248 bytes .../dmp/__pycache__/dmp.cpython-311.pyc | Bin 20199 -> 20199 bytes python/ur_simple_control/networking/client.py | 42 ++++- python/ur_simple_control/networking/server.py | 2 +- .../__pycache__/get_model.cpython-311.pyc | Bin 18550 -> 18550 bytes .../__pycache__/logging_utils.cpython-311.pyc | Bin 7294 -> 7294 bytes .../__pycache__/visualize.cpython-311.pyc | Bin 19644 -> 19644 bytes 17 files changed, 389 insertions(+), 58 deletions(-) create mode 100644 Dockerfile_no_conda create mode 100644 python/examples/graz/protobuf_ros1_bridge.py diff --git a/Dockerfile_no_conda b/Dockerfile_no_conda new file mode 100644 index 0000000..d9735f9 --- /dev/null +++ b/Dockerfile_no_conda @@ -0,0 +1,86 @@ +FROM ubuntu:jammy + +LABEL org.opencontainers.image.authors="marko.guberina@control.lth.se" + +# install python3-tk without questions +ARG DEBIAN_FRONTEND=noninteractive +ENV TZ=Europe/Stockholm + +RUN apt-get update && apt-get install -y --no-install-recommends \ + python3 \ + python3-pip \ + python3-tk \ + #ipython3 \ + git \ + sudo \ +# man-db \ +# manpages-posix \ + iputils-ping \ + arp-scan \ + # nice to have +# python3-opencv \ + vim \ + vim-addon-manager \ + vim-youcompleteme \ + vim-python-jedi \ + zsh \ + zsh-syntax-highlighting \ + libarchive-tools \ + libxcb-cursor0\ + python3-python-qt-binding + +# qt-binding is a really unnecessary 300MB, but i don't want +# to do more matplotlib hacks +# if you want manuals: +#RUN sed -i 's:^path-exclude=/usr/share/man:#path-exclude=/usr/share/man:' \ +# /etc/dpkg/dpkg.cfg.d/excludes +# we're running out of space on the docker.control +# and noone is reading manuals anyway +#RUN yes | unminimize + +# make the environment more usable +# create user +RUN useradd -m -s /bin/zsh -G sudo -u 1000 student + +WORKDIR /home/student/ +RUN passwd -d student +USER student +# copy repo to workdir +RUN mkdir SimpleManipulatorControl +COPY --chown=student . ./SimpleManipulatorControl +RUN mkdir -p .cache/zsh/ +COPY --chown=student /dot_files_for_docker/.vimrc /home/student/ +COPY --chown=student /dot_files_for_docker/.zshrc /home/student/ +COPY --chown=student /dot_files_for_docker/global_extra_conf.py /home/student/ + + +# sh does not have sourcing +# and some packages (conda) want shell environment variables +# (which i can say a lot about, but can't do anything about) +# ((the only reason to even use conda is to not have to compile pinocchio)) +SHELL ["/bin/bash", "--login", "-c"] +#SHELL ["/bin/bash"] + +# this is enough to run clik +WORKDIR /home/student/ +USER student +# TODO: install casadi and pinochio 3.0+ +# TODO: verify this stuff below works +# --> this can be done with conda +#RUN mkdir -p ~/miniconda3 +#RUN wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O /home/student/miniconda3/miniconda.sh +#RUN bash /home/student/miniconda3/miniconda.sh -b -u -p ~/miniconda3 +#RUN rm /home/student/miniconda3/miniconda.sh +#ENV PATH=/home/student/miniconda3/bin:$PATH +#RUN source /home/student/miniconda3/bin/activate +RUN pip install -e ./SimpleManipulatorControl/python/ +#RUN conda config --add channels conda-forge +#RUN conda install --solver=classic conda-forge::conda-libmamba-solver conda-forge::libmamba conda-forge::libmambapy conda-forge::libarchive +#RUN conda install --solver=classic -y pinocchio crocoddyl -c conda-forge +#RUN conda install -y pinocchio crocoddyl -c conda-forge +#RUN conda install -y opencv +RUN pip install pinocchio crocoddyl matplotlib meshcat ur_rtde argcomplete \ + qpsolvers ecos example_robot_data meshcat_shapes \ + pyqt6 opencv-python + +RUN vam install python-jedi && vam install youcompleteme diff --git a/python/examples/graz/cartesian_pose_command_server.py b/python/examples/graz/cartesian_pose_command_server.py index 8611aad..3e04dfc 100644 --- a/python/examples/graz/cartesian_pose_command_server.py +++ b/python/examples/graz/cartesian_pose_command_server.py @@ -4,14 +4,14 @@ from ur_simple_control.managers import ( ProcessManager, getMinimalArgParser, ) -from ur_simple_control.networking.server import server -from ur_simple_control.networking.client import client +from ur_simple_control.networking.server import server_sender +from ur_simple_control.networking.client import client_receiver import time def getArgs(): parser = getMinimalArgParser() - parser.description = "simple test program. sends commands to go in a circle, receives and prints out wrenches received by the client executing the go-in-circle commands" + parser.description = "simple test program. sends commands to go in a circle, receives and prints out wrenches received by the client_receiver executing the go-in-circle commands" parser.add_argument("--host", type=str, help="host ip address", default="127.0.0.1") parser.add_argument("--port", type=int, help="host's port", default=7777) @@ -49,12 +49,16 @@ if __name__ == "__main__": # command_sender: 7777 sender = ProcessManager( - args, server, {"T_goal": pin.SE3.Identity(), "v": np.zeros(6)}, 0 + args, server_sender, {"T_goal": pin.SE3.Identity(), "v": np.zeros(6)}, 0 ) # wrench_receiver: 6666 args.port = 6666 receiver = ProcessManager( - args, client, {"wrench": np.zeros(6)}, 4, init_value={"wrench": np.zeros(6)} + args, + client_receiver, + {"wrench": np.zeros(6)}, + 4, + init_value={"wrench": np.zeros(6)}, ) freq = 200 i = 0 diff --git a/python/examples/graz/clik_client.py b/python/examples/graz/clik_client.py index 1615311..95828d7 100644 --- a/python/examples/graz/clik_client.py +++ b/python/examples/graz/clik_client.py @@ -1,8 +1,8 @@ import pinocchio as pin import numpy as np from functools import partial -from ur_simple_control.networking.client import client -from ur_simple_control.networking.server import server +from ur_simple_control.networking.client import client_receiver, client_sender +from ur_simple_control.networking.server import server_sender from ur_simple_control.clik.clik import * from ur_simple_control.managers import ( ProcessManager, @@ -18,7 +18,8 @@ def get_args(): parser.description = "the robot will received joint angles from a socket and go to them in joint space" # add more arguments here from different Simple Manipulator Control modules parser.add_argument("--host", type=str, help="host ip address", default="127.0.0.1") - parser.add_argument("--port", type=int, help="host's port", default=7777) + parser.add_argument("--port-wrench", type=int, help="host's port", default=6666) + parser.add_argument("--port-command", type=int, help="host's port", default=7777) args = parser.parse_args() return args @@ -44,8 +45,9 @@ def controlLoopClikExternalGoal( T_w_e = robot.getT_w_e() data = receiver.getData() T_goal = data["T_goal"] - #print("translation:", T_goal.translation) - #print("rotation:", pin.Quaternion(T_goal.rotation)) + print(T_goal) + # print("translation:", T_goal.translation) + # print("rotation:", pin.Quaternion(T_goal.rotation)) SEerror = T_w_e.actInv(T_goal) err_vector = pin.log6(SEerror).vector J = pin.computeFrameJacobian(robot.model, robot.data, q, robot.ee_frame_id) @@ -88,16 +90,17 @@ if __name__ == "__main__": # VERY important that the first q we'll pass as desired is the current q, meaning the robot won't move # this is set with init_value # command_sender: 7777 + args.port = args.port_command receiver = ProcessManager( args, - client, + client_receiver, {"T_goal": pin.SE3.Identity(), "v": np.zeros(6)}, 4, init_value={"T_goal": robot.getT_w_e(), "v": np.zeros(6)}, ) # wrench_sender: 6666 - args.port = 6666 - sender = ProcessManager(args, server, {"wrench": np.zeros(6)}, 0) + args.port = args.port_wrench + sender = ProcessManager(args, client_sender, {"wrench": np.zeros(6)}, 0) log_item = { "qs": np.zeros((robot.model.nq,)), "dqs": np.zeros((robot.model.nv,)), diff --git a/python/examples/graz/joint_copier_client.py b/python/examples/graz/joint_copier_client.py index 00bc0af..e34396c 100644 --- a/python/examples/graz/joint_copier_client.py +++ b/python/examples/graz/joint_copier_client.py @@ -1,7 +1,7 @@ import pinocchio as pin import numpy as np from functools import partial -from ur_simple_control.networking.client import client +from ur_simple_control.networking.client import client_receiver from ur_simple_control.managers import ( ProcessManager, getMinimalArgParser, @@ -56,7 +56,11 @@ if __name__ == "__main__": # VERY important that the first q we'll pass as desired is the current q, meaning the robot won't move # this is set with init_value receiver = ProcessManager( - args, client, {"q": robot.q.copy()}, 4, init_value={"q": robot.q.copy()} + args, + client_receiver, + {"q": robot.q.copy()}, + 4, + init_value={"q": robot.q.copy()}, ) log_item = { "qs": np.zeros((robot.model.nq,)), diff --git a/python/examples/graz/point_impedance_server.py b/python/examples/graz/point_impedance_server.py index 260efaf..0c66439 100644 --- a/python/examples/graz/point_impedance_server.py +++ b/python/examples/graz/point_impedance_server.py @@ -16,7 +16,7 @@ from ur_simple_control.managers import ( ControlLoopManager, RobotManager, ) -from ur_simple_control.networking.server import server +from ur_simple_control.networking.server import server_sender def getArgs(): @@ -199,7 +199,7 @@ if __name__ == "__main__": } q_init = robot.getQ() Mtool_init = robot.getT_w_e() - sender = ProcessManager(args, server, {"q": np.zeros(6)}, 0) + sender = ProcessManager(args, server_sender, {"q": np.zeros(6)}, 0) if not args.cartesian_space_impedance: controlLoop = partial( diff --git a/python/examples/graz/protobuf_ros1_bridge.py b/python/examples/graz/protobuf_ros1_bridge.py new file mode 100644 index 0000000..4c412c9 --- /dev/null +++ b/python/examples/graz/protobuf_ros1_bridge.py @@ -0,0 +1,171 @@ +import socket +from google.protobuf.internal.encoder import _VarintBytes +from google.protobuf.internal.decoder import _DecodeVarint32 +import argparse +import message_specs_pb2 +from functools import partial +import importlib.util +import random +import time +from threading import Thread + +if importlib.util.find_spec("rospy"): + from agents_test.msg import Command + import rospy + from geometry_msgs.msg import WrenchStamped + + +def getArgs(): + parser = argparse.ArgumentParser() + parser.description = ( + "get ros1 message, make it a protobuf message, send it via tcp socket" + ) + parser.add_argument("--host", type=str, help="host ip address", default="127.0.0.1") + parser.add_argument( + "--port-wrench", type=int, help="host's port for receiving wrench", default=6666 + ) + parser.add_argument("--port-command", type=int, help="host's port", default=7777) + + args = parser.parse_args() + return args + + +def command_callback(command_socket, c): + position = [c.goal.position.x, c.goal.position.y, c.goal.position.z] + orientation = [ + c.goal.orientation.w, + c.goal.orientation.x, + c.goal.orientation.y, + c.goal.orientation.z, + ] + position_vel = [c.goal_dot.position.x, c.goal_dot.position.y, c.goal_dot.position.z] + orientation_vel = [ + c.goal_dot.orientation.w, + c.goal_dot.orientation.x, + c.goal_dot.orientation.y, + ] + pb2_msg = message_specs_pb2.T_goal() + pb2_msg.position.extend(position) + pb2_msg.rotation.extend(orientation) + pb2_msg.velocity.extend(position_vel + orientation_vel) + msg_length = pb2_msg.ByteSize() + msg_serialized = pb2_msg.SerializeToString() + msg = _VarintBytes(msg_length) + msg_serialized + command_socket.send(msg) + + +def sendRandomForTest(comm_socket): + while True: + pb2_msg = message_specs_pb2.T_goal() + pb2_msg.position.extend([random.random()] * 3) + pb2_msg.rotation.extend([random.random()] * 4) + pb2_msg.velocity.extend([random.random()] * 6) + msg_length = pb2_msg.ByteSize() + msg_serialized = pb2_msg.SerializeToString() + msg = _VarintBytes(msg_length) + msg_serialized + comm_socket.send(msg) + time.sleep(0.002) + + +def parse_message(buffer): + """ + parse_message + ------------- + here the message is what we got from recv(), + and parsing it refers to finding serialized pb2 messages in it + NOTE: we only keep the latest message because + we're not going to do anything with the missed message. + the assumption is that we only get the same kind of message from + a sensor or something similar, not files or whatever else needs to be whole + """ + pos, next_pos = 0, 0 + buffer_len = len(buffer) + msg_in_bytes = b"" + len_size_offset = 0 + while True: + next_pos, pos = _DecodeVarint32(buffer, pos) + if pos + next_pos > buffer_len: + return msg_in_bytes, pos - len_size_offset + msg_in_bytes = _VarintBytes(pos + next_pos) + buffer[pos : pos + next_pos] + len_size_offset = len(_VarintBytes(pos + next_pos)) + pos += next_pos + if pos >= buffer_len: + return msg_in_bytes, pos + + +def getCommandClient(args): + args = getArgs() + host_addr = (args.host, args.port_command) + s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + s.bind(host_addr) + print("NETWORKING_SERVER_COMMAND_SENDER listening on port ", args.port_command) + s.listen() + command_socket, comm_addr = s.accept() + # we're only accepting a single connection + s.close() + print("NETWORKING_SERVER_COMMAND_SENDER: accepted a client", comm_addr) + return command_socket + + +def getWrenchClient(args): + args = getArgs() + host_addr = (args.host, args.port_wrench) + s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + s.bind(host_addr) + print("NETWORKING_SERVER_COMMAND_SENDER listening on port ", args.port_wrench) + s.listen() + wrench_socket, comm_addr = s.accept() + # we're only accepting a single connection + s.close() + print("NETWORKING_SERVER_COMMAND_SENDER: accepted a client", comm_addr) + return wrench_socket + + +if __name__ == "__main__": + if importlib.util.find_spec("rospy"): + rospy.init_node("ros1_to_ur5e_mapper", anonymous=True) + ros1_exists = True + else: + ros1_exists = False + args = getArgs() + command_socket = getCommandClient(args) + wrench_socket = getWrenchClient(args) + + # ros subscriber + if ros1_exists: + callback_part = partial(command_callback, command_socket) + rospy.Subscriber("/robot_command", Command, callback_part) + pub = rospy.Publisher("wrench_msg_mapper", WrenchStamped, queue_size=10) + else: + t = Thread(target=sendRandomForTest, args=(command_socket,)) + t.run() + + buffer = b"" + while True: + # receive wrench as protobuf message + msg_raw = wrench_socket.recv(1024) + buffer += msg_raw + if len(msg_raw) < 1: + continue + msg_in_bytes, pos = parse_message(buffer) + buffer = buffer[pos:] + + next_pos, pos = 0, 0 + next_pos, pos = _DecodeVarint32(msg_in_bytes, pos) + pb2_msg_in_bytes_cut = msg_in_bytes[pos : pos + next_pos] + pb2_msg = message_specs_pb2.wrench() + pb2_msg.ParseFromString(pb2_msg_in_bytes_cut) + print(pb2_msg) + + # send wrench as ros1 message + if ros1_exists: + wrench_message = WrenchStamped() + wrench_message.wrench.force.x = pb2_msg.wrench[0] + wrench_message.wrench.force.y = pb2_msg.wrench[1] + wrench_message.wrench.force.z = pb2_msg.wrench[2] + wrench_message.wrench.torque.x = pb2_msg.wrench[3] + wrench_message.wrench.torque.y = pb2_msg.wrench[4] + wrench_message.wrench.torque.z = pb2_msg.wrench[5] + wrench_message.header.stamp = rospy.Time.now() + wrench_message.header.frame_id = 0 + pub.publish(wrench_message) diff --git a/python/examples/graz/protobuf_to_ros1.py b/python/examples/graz/protobuf_to_ros1.py index 2c3afcc..0b35f2b 100644 --- a/python/examples/graz/protobuf_to_ros1.py +++ b/python/examples/graz/protobuf_to_ros1.py @@ -1,11 +1,13 @@ import socket from google.protobuf.internal.encoder import _VarintBytes from google.protobuf.internal.decoder import _DecodeVarint32 -import time import argparse import message_specs_pb2 -import rospy -from geometry_msgs.msg import WrenchStamped +import importlib.util + +if importlib.util.find_spec("rospy"): + import rospy + from geometry_msgs.msg import WrenchStamped def getArgs(): @@ -47,27 +49,29 @@ def parse_message(buffer): return msg_in_bytes, pos - # ros parts -#rospy.init_node("ur5e_to_ros1_mapper", anonymous=True) -#pub = rospy.Publisher("wrench_msg_mapper", WrenchStamped, queue_size=10) +if importlib.util.find_spec("rospy"): + ros1_exists = True + rospy.init_node("ur5e_to_ros1_mapper", anonymous=True) + pub = rospy.Publisher("wrench_msg_mapper", WrenchStamped, queue_size=10) +else: + ros1_exists = False + args = getArgs() host_addr = (args.host, args.port) s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) +s.bind(host_addr) +print("listening on port ", args.port) +s.listen() +comm_socket, comm_addr = s.accept() +# we're only accepting a single connection +s.close() +print("NETWORKING_SERVER_RECEIVER: accepted a client", comm_addr) buffer = b"" -while True: - try: - s.connect(host_addr) - break - except ConnectionRefusedError: - time.sleep(0.005) -print("NETWORKING CLIENT: connected to server") -s.settimeout(None) -#try: while True: - msg_raw = s.recv(1024) + msg_raw = comm_socket.recv(1024) buffer += msg_raw print(msg_raw) print(len(msg_raw)) @@ -83,19 +87,15 @@ while True: pb2_msg.ParseFromString(pb2_msg_in_bytes_cut) print(pb2_msg.wrench) - # here you send construct and send the ros message - #wrench_message = WrenchStamped() - #wrench_message.wrench.force.x = pb2_msg.wrench[0] - #wrench_message.wrench.force.y = pb2_msg.wrench[1] - #wrench_message.wrench.force.z = pb2_msg.wrench[2] - #wrench_message.wrench.torque.x = pb2_msg.wrench[3] - #wrench_message.wrench.torque.y = pb2_msg.wrench[4] - #wrench_message.wrench.torque.z = pb2_msg.wrench[5] - #wrench_message.header.stamp = rospy.Time.now() - #wrench_message.header.frame_id = 0 - #pub.publish(wrench_message) - # time.sleep(0.002) - -#except KeyboardInterrupt: -# s.close() -# print("NETWORKING_CLIENT: caught KeyboardInterrupt, i'm out") + if ros1_exists: + # here you send construct and send the ros message + wrench_message = WrenchStamped() + wrench_message.wrench.force.x = pb2_msg.wrench[0] + wrench_message.wrench.force.y = pb2_msg.wrench[1] + wrench_message.wrench.force.z = pb2_msg.wrench[2] + wrench_message.wrench.torque.x = pb2_msg.wrench[3] + wrench_message.wrench.torque.y = pb2_msg.wrench[4] + wrench_message.wrench.torque.z = pb2_msg.wrench[5] + wrench_message.header.stamp = rospy.Time.now() + wrench_message.header.frame_id = 0 + pub.publish(wrench_message) diff --git a/python/examples/graz/ros1_to_protobuf.py b/python/examples/graz/ros1_to_protobuf.py index 9eb487e..23b9a47 100644 --- a/python/examples/graz/ros1_to_protobuf.py +++ b/python/examples/graz/ros1_to_protobuf.py @@ -2,11 +2,15 @@ import socket from google.protobuf.internal.encoder import _VarintBytes import argparse import message_specs_pb2 +import random +import importlib.util import time -from agents_test.msg import Command -import rospy from functools import partial +if importlib.util.find_spec("rospy"): + from agents_test.msg import Command + import rospy + def getArgs(): parser = argparse.ArgumentParser() @@ -46,8 +50,25 @@ def callback(comm_socket, c): comm_socket.send(msg) +def sendRandomForTest(comm_socket): + pb2_msg = message_specs_pb2.T_goal() + pb2_msg.position.extend([random.random()] * 3) + pb2_msg.rotation.extend([random.random()] * 4) + pb2_msg.velocity.extend([random.random()] * 6) + # print(pb2_msg) + msg_length = pb2_msg.ByteSize() + msg_serialized = pb2_msg.SerializeToString() + msg = _VarintBytes(msg_length) + msg_serialized + comm_socket.send(msg) + time.sleep(0.002) + + if __name__ == "__main__": - rospy.init_node("ros1_to_ur5e_mapper", anonymous=True) + if importlib.util.find_spec("rospy"): + rospy.init_node("ros1_to_ur5e_mapper", anonymous=True) + ros1_exists = True + else: + ros1_exists = False args = getArgs() host_addr = (args.host, args.port) s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) @@ -61,9 +82,13 @@ if __name__ == "__main__": print("NETWORKING_SERVER: accepted a client", comm_addr) # ros subscriber - callback_part = partial(callback, comm_socket) - rospy.Subscriber("/robot_command", Command, callback_part) - rospy.spin() + if ros1_exists: + callback_part = partial(callback, comm_socket) + rospy.Subscriber("/robot_command", Command, callback_part) + rospy.spin() + else: + while True: + sendRandomForTest(comm_socket) comm_socket.close() diff --git a/python/ur_simple_control/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/__pycache__/__init__.cpython-311.pyc index 83e8dc1caa549a0c48d4b1b555bf9f81c9281138..254c84a11fc8c60bbcfaee9c36e4a862c87e1e19 100644 GIT binary patch delta 20 ccmaFC{DPT#IWI340|Ns?<og91x$iOp06z%^F8}}l delta 20 bcmaFC{DPT#IWI340|NuYz9^rK+;<rPJgNn& diff --git a/python/ur_simple_control/__pycache__/managers.cpython-311.pyc b/python/ur_simple_control/__pycache__/managers.cpython-311.pyc index 97057c8041c533926c4dc301dcf62c471326ec28..694dcc15a77d3d7eb33a5860e00f52bb41d3f418 100644 GIT binary patch delta 21 dcmX?fkNMC&X0GMDyj%<n3=EO)H*#6L2LM!$2Sxw@ delta 21 dcmX?fkNMC&X0GMDyj%<n3=B#SHgZ|K2LMv~2LJ#7 diff --git a/python/ur_simple_control/clik/__pycache__/__init__.cpython-311.pyc b/python/ur_simple_control/clik/__pycache__/__init__.cpython-311.pyc index 22beafda9e5a29c24a3dc6f2ff7234ca612005bd..434ef404cf030ac6960723afbe8fbd897f55614f 100644 GIT binary patch delta 19 bcmeyt_=AyqIWI340|Ns?<og8^x!(c+I)(;1 delta 19 acmeyt_=AyqIWI340|NuY^zP7!+;0Im+6Bn~ diff --git a/python/ur_simple_control/dmp/__pycache__/dmp.cpython-311.pyc b/python/ur_simple_control/dmp/__pycache__/dmp.cpython-311.pyc index c5479ed52b6db36c9b993efa9e233fa29bc93cf1..d34fdb7c319f1b550e77838c5f2ad7c992d5bb82 100644 GIT binary patch delta 22 ecmaDpm+|>rM(*Xjyj%<n3=EO)7i{Fd;|Bm)i3hI$ delta 22 ecmaDpm+|>rM(*Xjyj%<n3=E-~b{o0x_yGV?-v)yK diff --git a/python/ur_simple_control/networking/client.py b/python/ur_simple_control/networking/client.py index 2e23f47..2cc4d94 100644 --- a/python/ur_simple_control/networking/client.py +++ b/python/ur_simple_control/networking/client.py @@ -7,7 +7,7 @@ import pickle import time -def client(args, init_command, shm_name, lock): +def client_receiver(args, init_command, shm_name, lock): """ client ------- @@ -66,7 +66,7 @@ def client(args, init_command, shm_name, lock): except ConnectionRefusedError: time.sleep(0.005) if args.debug_prints: - print("NETWORKING CLIENT: connected to server") + print("NETWORKING CLIENT_RECEIVER: connected to server") try: while True: @@ -106,3 +106,41 @@ def client(args, init_command, shm_name, lock): s.close() if args.debug_prints: print("NETWORKING_CLIENT: caught KeyboardInterrupt, i'm out") + + +def client_sender(args, init_command, queue): + """ + server + ------- + listens for a connection, then sends messages to the singular accepted client + + ex. host = "127.0.0.1" + ex. host_port = 7777 + + use comm_direction = 0 in processmanager for this + """ + encoder_decoder = DictPb2EncoderDecoder() + host_addr = (args.host, args.port) + s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + while True: + try: + s.connect(host_addr) + break + except ConnectionRefusedError: + time.sleep(0.005) + if args.debug_prints: + print("NETWORKING CLIENT_SENDER: connected to server") + + try: + while True: + # the construction of the message should happen in processmanager + msg_dict = queue.get() + if msg_dict == "befree": + if args.debug_prints: + print("NETWORKING_SERVER: got befree, networking server out") + break + s.send(encoder_decoder.dictToSerializedPb2Msg(msg_dict)) + except KeyboardInterrupt: + if args.debug_prints: + print("NETWORKING_SERVER: caugth KeyboardInterrupt, networking server out") + s.close() diff --git a/python/ur_simple_control/networking/server.py b/python/ur_simple_control/networking/server.py index f3bd566..39e112e 100644 --- a/python/ur_simple_control/networking/server.py +++ b/python/ur_simple_control/networking/server.py @@ -3,7 +3,7 @@ from google.protobuf.internal.encoder import _VarintBytes from ur_simple_control.networking.util import DictPb2EncoderDecoder -def server(args, init_command, queue): +def server_sender(args, init_command, queue): """ server ------- diff --git a/python/ur_simple_control/util/__pycache__/get_model.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/get_model.cpython-311.pyc index 434ecea554d17d59d10efe9ced81a04145265c2d..27ce8990a08fb141252db94f8dac8142eb9f7535 100644 GIT binary patch delta 21 dcmex1f$`e}My}<&yj%<n3=EO)H*)28002<12Aco? delta 21 dcmex1f$`e}My}<&yj%<n3=HNEHge^7002*!25JBR diff --git a/python/ur_simple_control/util/__pycache__/logging_utils.cpython-311.pyc b/python/ur_simple_control/util/__pycache__/logging_utils.cpython-311.pyc index fbd1ed2ac5e0c105c2a48f4977dd704e6ef03896..281e3f4efb188f9df078eb620e9ca6a200500994 100644 GIT binary patch delta 20 bcmexo@y~*LIWI340|Ns?<og91xr=20NeBjZ delta 20 bcmexo@y~*LIWI340|Ntt%X-_5+{H2gMFs`F diff --git a/python/ur_simple_control/visualize/__pycache__/visualize.cpython-311.pyc b/python/ur_simple_control/visualize/__pycache__/visualize.cpython-311.pyc index c34b2cf67deaa3275c474abf33199ce0e6406ff1..85f6de7bf9de87d0277befb626529d2838866f6a 100644 GIT binary patch delta 22 ecmdlplX1^XM(*Xjyj%<n3=EO)7i{F-=mP*zvIisp delta 22 ecmdlplX1^XM(*Xjyj%<n3=DUdrf%fk=mP*!YX>6$ -- GitLab