Skip to content

Commit c56f558

Browse files
LaurieCheers-unityprothenmrpropellersat669
authored
Merge dev into main - Version 0.2.0 (#39)
* Add logging dependency (#32) * Changing yamato host flavor to large (#33) Co-authored-by: Philipp Rothenhäusler <phirot@kth.se> Co-authored-by: Devin Miller (Unity) <mrpropellers@users.noreply.github.com> Co-authored-by: Amanda <31416491+at669@users.noreply.github.com>
1 parent aee36db commit c56f558

File tree

4 files changed

+19
-16
lines changed

4 files changed

+19
-16
lines changed

.yamato/yamato-config.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ name: Endpoint Unit Tests
22
agent:
33
type: Unity::VM
44
image: robotics/ci-ubuntu20:latest
5-
flavor: i1.medium
5+
flavor: i1.large
66
commands:
77
- source /opt/ros/noetic/setup.bash && echo "ROS_DISTRO == $ROS_DISTRO" &&
88
cd .. && mkdir -p catkin_ws/src && cp -r ./ROS-TCP-Endpoint catkin_ws/src &&

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>ros_tcp_endpoint</name>
4-
<version>0.1.2</version>
4+
<version>0.2.0</version>
55
<description>Acts as the bridge between Unity messages sent via Websocket and ROS messages.</description>
66

77
<maintainer email="unity-robotics@unity3d.com">Unity Robotics</maintainer>

src/ros_tcp_endpoint/server.py

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,11 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
import sys
16+
import json
1517
import rospy
1618
import socket
17-
import json
18-
import sys
19+
import logging
1920
import threading
2021
import importlib
2122

@@ -30,7 +31,7 @@ class TcpServer:
3031
Initializes ROS node and TCP server.
3132
"""
3233

33-
def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip="", tcp_port=-1):
34+
def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip="", tcp_port=-1, timeout=10):
3435
"""
3536
Initializes ROS node and class variables.
3637
@@ -43,15 +44,15 @@ def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip="", tcp_p
4344
self.tcp_ip = tcp_ip
4445
else:
4546
self.tcp_ip = rospy.get_param("/ROS_IP")
46-
47+
4748
if tcp_port != -1:
4849
self.tcp_port = tcp_port
4950
else:
5051
self.tcp_port = rospy.get_param("/ROS_TCP_PORT", 10000)
5152

5253
unity_machine_ip = rospy.get_param("/UNITY_IP", '')
5354
unity_machine_port = rospy.get_param("/UNITY_SERVER_PORT", 5005)
54-
self.unity_tcp_sender = UnityTcpSender(unity_machine_ip, unity_machine_port)
55+
self.unity_tcp_sender = UnityTcpSender(unity_machine_ip, unity_machine_port, timeout)
5556

5657
self.node_name = node_name
5758
self.source_destination_dict = {}
@@ -66,7 +67,7 @@ def start(self, source_destination_dict=None):
6667
# Exit the server thread when the main thread terminates
6768
server_thread.daemon = True
6869
server_thread.start()
69-
70+
7071
def listen_loop(self):
7172
"""
7273
Creates and binds sockets using TCP variables then listens for incoming connections.
@@ -122,7 +123,7 @@ def subscribe(self, topic, message_name):
122123
return
123124

124125
rospy.loginfo("RegisterSubscriber({}, {}) OK".format(topic, message_class))
125-
126+
126127
if topic in self.tcp_server.source_destination_dict:
127128
self.tcp_server.source_destination_dict[topic].unregister()
128129

@@ -140,10 +141,10 @@ def publish(self, topic, message_name):
140141
return
141142

142143
rospy.loginfo("RegisterPublisher({}, {}) OK".format(topic, message_class))
143-
144+
144145
if topic in self.tcp_server.source_destination_dict:
145146
self.tcp_server.source_destination_dict[topic].unregister()
146-
147+
147148
self.tcp_server.source_destination_dict[topic] = RosPublisher(topic, message_class, queue_size=10)
148149

149150

src/ros_tcp_endpoint/tcp_sender.py

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -23,11 +23,12 @@ class UnityTcpSender:
2323
"""
2424
Connects and sends messages to the server on the Unity side.
2525
"""
26-
def __init__(self, unity_ip, unity_port):
26+
def __init__(self, unity_ip, unity_port, timeout):
2727
self.unity_ip = unity_ip
2828
self.unity_port = unity_port
2929
# if we have a valid IP at this point, it was overridden locally so always use that
3030
self.ip_is_overridden = (self.unity_ip != '')
31+
self.timeout = timeout
3132

3233
def handshake(self, incoming_ip, data):
3334
message = UnityHandshake._request_class().deserialize(data)
@@ -55,10 +56,10 @@ def send_unity_message(self, topic, message):
5556

5657
try:
5758
s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
58-
s.settimeout(2)
59+
s.settimeout(self.timeout)
5960
s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
6061
s.connect((self.unity_ip, self.unity_port))
61-
s.send(serialized_message)
62+
s.sendall(serialized_message)
6263
s.close()
6364
except Exception as e:
6465
rospy.loginfo("Exception {}".format(e))
@@ -72,10 +73,10 @@ def send_unity_service(self, topic, service_class, request):
7273

7374
try:
7475
s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
75-
s.settimeout(2)
76+
s.settimeout(self.timeout)
7677
s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
7778
s.connect((self.unity_ip, self.unity_port))
78-
s.send(serialized_message)
79+
s.sendall(serialized_message)
7980

8081
destination, data = ClientThread.read_message(s)
8182

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

0 commit comments

Comments
 (0)