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

Amanda/read chunks #36

Merged
merged 3 commits into from
Feb 10, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
4 changes: 2 additions & 2 deletions src/ros_tcp_endpoint/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class TcpServer:
Initializes ROS node and TCP server.
"""

def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip="", tcp_port=-1):
def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip="", tcp_port=-1, timeout=10):
"""
Initializes ROS node and class variables.

Expand All @@ -52,7 +52,7 @@ def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip="", tcp_p

unity_machine_ip = rospy.get_param("/UNITY_IP", '')
unity_machine_port = rospy.get_param("/UNITY_SERVER_PORT", 5005)
self.unity_tcp_sender = UnityTcpSender(unity_machine_ip, unity_machine_port)
self.unity_tcp_sender = UnityTcpSender(unity_machine_ip, unity_machine_port, timeout)

self.node_name = node_name
self.source_destination_dict = {}
Expand Down
12 changes: 7 additions & 5 deletions src/ros_tcp_endpoint/tcp_sender.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,12 @@ class UnityTcpSender:
"""
Connects and sends messages to the server on the Unity side.
"""
def __init__(self, unity_ip, unity_port):
def __init__(self, unity_ip, unity_port, timeout):
self.unity_ip = unity_ip
self.unity_port = unity_port
# if we have a valid IP at this point, it was overridden locally so always use that
self.ip_is_overridden = (self.unity_ip != '')
self.timeout = timeout

def handshake(self, incoming_ip, data):
message = UnityHandshake._request_class().deserialize(data)
Expand Down Expand Up @@ -55,10 +56,10 @@ def send_unity_message(self, topic, message):

try:
s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
s.settimeout(2)
s.settimeout(self.timeout)
s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
s.connect((self.unity_ip, self.unity_port))
s.send(serialized_message)
s.sendall(serialized_message)
s.close()
except Exception as e:
rospy.loginfo("Exception {}".format(e))
Expand All @@ -72,10 +73,10 @@ def send_unity_service(self, topic, service_class, request):

try:
s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
s.settimeout(2)
s.settimeout(self.timeout)
s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
s.connect((self.unity_ip, self.unity_port))
s.send(serialized_message)
s.sendall(serialized_message)

destination, data = ClientThread.read_message(s)

Expand All @@ -85,3 +86,4 @@ def send_unity_service(self, topic, service_class, request):
return response
except Exception as e:
rospy.loginfo("Exception {}".format(e))