Skip to content

Commit aee36db

Browse files
Merge pull request #31 from Unity-Technologies/dev
Release 0.1.2
2 parents b61ba41 + 49d7b71 commit aee36db

File tree

12 files changed

+185
-45
lines changed

12 files changed

+185
-45
lines changed

.yamato/yamato-config.yml

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
name: Endpoint Unit Tests
2+
agent:
3+
type: Unity::VM
4+
image: robotics/ci-ubuntu20:latest
5+
flavor: i1.medium
6+
commands:
7+
- source /opt/ros/noetic/setup.bash && echo "ROS_DISTRO == $ROS_DISTRO" &&
8+
cd .. && mkdir -p catkin_ws/src && cp -r ./ROS-TCP-Endpoint catkin_ws/src &&
9+
cd catkin_ws && catkin_make && source devel/setup.bash && python3 -m pytest
10+
triggers:
11+
cancel_old_ci: true
12+
expression: |
13+
(pull_request.target eq "main" AND
14+
NOT pull_request.push.changes.all match "**/*.md") OR
15+
(push.branch eq "dev" AND
16+
NOT push.changes.all match "**/*.md")

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.0.1</version>
4+
<version>0.1.2</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/client.py

Lines changed: 37 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -40,23 +40,25 @@ def __init__(self, conn, tcp_server, incoming_ip, incoming_port):
4040
self.incoming_ip = incoming_ip
4141
self.incoming_port = incoming_port
4242

43-
def read_int32(self):
43+
@staticmethod
44+
def read_int32(conn):
4445
"""
4546
Reads four bytes from socket connection and unpacks them to an int
4647
4748
Returns: int
4849
4950
"""
5051
try:
51-
raw_bytes = self.conn.recv(4)
52+
raw_bytes = conn.recv(4)
5253
num = struct.unpack('<I', raw_bytes)[0]
5354
return num
5455
except Exception as e:
5556
print("Unable to read integer from connection. {}".format(e))
5657

5758
return None
5859

59-
def read_string(self):
60+
@staticmethod
61+
def read_string(conn):
6062
"""
6163
Reads int32 from socket connection to determine how many bytes to
6264
read to get the string that follows. Read that number of bytes and
@@ -66,9 +68,9 @@ def read_string(self):
6668
6769
"""
6870
try:
69-
str_len = self.read_int32()
71+
str_len = ClientThread.read_int32(conn)
7072

71-
str_bytes = self.conn.recv(str_len)
73+
str_bytes = conn.recv(str_len)
7274
decoded_str = str_bytes.decode('utf-8')
7375

7476
return decoded_str
@@ -78,6 +80,34 @@ def read_string(self):
7880

7981
return None
8082

83+
@staticmethod
84+
def read_message(conn):
85+
"""
86+
Decode destination and full message size from socket connection.
87+
Grab bytes in chunks until full message has been read.
88+
"""
89+
data = b''
90+
91+
destination = ClientThread.read_string(conn)
92+
full_message_size = ClientThread.read_int32(conn)
93+
94+
while len(data) < full_message_size:
95+
# Only grabs max of 1024 bytes TODO: change to TCPServer's buffer_size
96+
grab = 1024 if full_message_size - len(data) > 1024 else full_message_size - len(data)
97+
packet = conn.recv(grab)
98+
99+
if not packet:
100+
print("No packets...")
101+
break
102+
103+
data += packet
104+
105+
if not data:
106+
print("No data for a message size of {}, breaking!".format(full_message_size))
107+
return
108+
109+
return destination, data
110+
81111
@staticmethod
82112
def serialize_message(destination, message):
83113
"""
@@ -111,9 +141,7 @@ def serialize_message(destination, message):
111141

112142
def run(self):
113143
"""
114-
Decode destination and full message size from socket connection.
115-
Grab bytes in chunks until full message has been read.
116-
Determine where to send the message based on the source_destination_dict
144+
Read a message and determine where to send it based on the source_destination_dict
117145
and destination string. Then send the read message.
118146
119147
If there is a response after sending the serialized data, assume it is a
@@ -126,25 +154,7 @@ def run(self):
126154
msg: the ROS msg type as bytes
127155
128156
"""
129-
data = b''
130-
131-
destination = self.read_string()
132-
full_message_size = self.read_int32()
133-
134-
while len(data) < full_message_size:
135-
# Only grabs max of 1024 bytes TODO: change to TCPServer's buffer_size
136-
grab = 1024 if full_message_size - len(data) > 1024 else full_message_size - len(data)
137-
packet = self.conn.recv(grab)
138-
139-
if not packet:
140-
print("No packets...")
141-
break
142-
143-
data += packet
144-
145-
if not data:
146-
print("No data for a message size of {}, breaking!".format(full_message_size))
147-
return
157+
destination, data = self.read_message(self.conn)
148158

149159
if destination == '__syscommand':
150160
self.tcp_server.handle_syscommand(data)

src/ros_tcp_endpoint/default_server_endpoint.py

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,6 @@
11
#!/usr/bin/env python
22

33
import rospy
4-
import actionlib_msgs.msg
5-
import diagnostic_msgs.msg
6-
import geometry_msgs.msg
7-
import nav_msgs.msg
8-
import sensor_msgs.msg
9-
import shape_msgs.msg
10-
import stereo_msgs.msg
11-
import trajectory_msgs.msg
12-
import visualization_msgs.msg
134

145
from ros_tcp_endpoint import TcpServer
156

src/ros_tcp_endpoint/publisher.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,4 +56,4 @@ def unregister(self):
5656
Returns:
5757
5858
"""
59-
self.pub.unregister()
59+
self.pub.unregister()

src/ros_tcp_endpoint/server.py

Lines changed: 19 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
import json
1818
import sys
1919
import threading
20+
import importlib
2021

2122
from .tcp_sender import UnityTcpSender
2223
from .client import ClientThread
@@ -29,7 +30,7 @@ class TcpServer:
2930
Initializes ROS node and TCP server.
3031
"""
3132

32-
def __init__(self, node_name, buffer_size=1024, connections=10):
33+
def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip="", tcp_port=-1):
3334
"""
3435
Initializes ROS node and class variables.
3536
@@ -38,8 +39,15 @@ def __init__(self, node_name, buffer_size=1024, connections=10):
3839
buffer_size: The read buffer size used when reading from a socket
3940
connections: Max number of queued connections. See Python Socket documentation
4041
"""
41-
self.tcp_ip = rospy.get_param("/ROS_IP")
42-
self.tcp_port = rospy.get_param("/ROS_TCP_PORT", 10000)
42+
if tcp_ip != "":
43+
self.tcp_ip = tcp_ip
44+
else:
45+
self.tcp_ip = rospy.get_param("/ROS_IP")
46+
47+
if tcp_port != -1:
48+
self.tcp_port = tcp_port
49+
else:
50+
self.tcp_port = rospy.get_param("/ROS_TCP_PORT", 10000)
4351

4452
unity_machine_ip = rospy.get_param("/UNITY_IP", '')
4553
unity_machine_port = rospy.get_param("/UNITY_SERVER_PORT", 5005)
@@ -51,7 +59,9 @@ def __init__(self, node_name, buffer_size=1024, connections=10):
5159
self.connections = connections
5260
self.syscommands = SysCommands(self)
5361

54-
def start(self):
62+
def start(self, source_destination_dict=None):
63+
if source_destination_dict is not None:
64+
self.source_destination_dict = source_destination_dict
5565
server_thread = threading.Thread(target=self.listen_loop)
5666
# Exit the server thread when the main thread terminates
5767
server_thread.daemon = True
@@ -82,6 +92,9 @@ def send_unity_error(self, error):
8292
def send_unity_message(self, topic, message):
8393
self.unity_tcp_sender.send_unity_message(topic, message)
8494

95+
def send_unity_service(self, topic, service_class, request):
96+
return self.unity_tcp_sender.send_unity_service(topic, service_class, request)
97+
8598
def handle_syscommand(self, data):
8699
message = RosUnitySysCommand().deserialize(data)
87100
function = getattr(self.syscommands, message.command)
@@ -139,6 +152,7 @@ def resolve_message_name(name):
139152
names = name.split('/')
140153
module_name = names[0]
141154
class_name = names[1]
155+
importlib.import_module(module_name+ ".msg")
142156
module = sys.modules[module_name]
143157
if module is None:
144158
rospy.loginfo("Failed to resolve module {}".format(module_name))
@@ -150,4 +164,5 @@ def resolve_message_name(name):
150164
rospy.loginfo("Failed to resolve module {}.msg.{}".format(module_name, class_name))
151165
return module
152166
except (IndexError, KeyError, AttributeError) as e:
167+
rospy.loginfo("Exception Raised: {}".format(e))
153168
return None

src/ros_tcp_endpoint/service.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,4 +67,4 @@ def unregister(self):
6767
6868
"""
6969
if not self.srv is None:
70-
self.srv.close()
70+
self.srv.close()

src/ros_tcp_endpoint/subscriber.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@ def __init__(self, topic, message_class, tcp_server, queue_size=10):
3232
message_class: The message class in catkin workspace
3333
queue_size: Max number of entries to maintain in an outgoing queue
3434
"""
35+
RosReceiver.__init__(self)
3536
self.topic = topic
3637
self.node_name = "{}_subscriber".format(topic)
3738
self.msg = message_class
@@ -62,4 +63,4 @@ def unregister(self):
6263
6364
"""
6465
if not self.sub is None:
65-
self.sub.unregister()
66+
self.sub.unregister()

src/ros_tcp_endpoint/tcp_sender.py

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,4 +61,27 @@ def send_unity_message(self, topic, message):
6161
s.send(serialized_message)
6262
s.close()
6363
except Exception as e:
64-
rospy.loginfo("Exception {}".format(e))
64+
rospy.loginfo("Exception {}".format(e))
65+
66+
def send_unity_service(self, topic, service_class, request):
67+
if self.unity_ip == '':
68+
print("Can't send a message, no defined unity IP!".format(topic, request))
69+
return
70+
71+
serialized_message = ClientThread.serialize_message(topic, request)
72+
73+
try:
74+
s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
75+
s.settimeout(2)
76+
s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
77+
s.connect((self.unity_ip, self.unity_port))
78+
s.send(serialized_message)
79+
80+
destination, data = ClientThread.read_message(s)
81+
82+
response = service_class._response_class().deserialize(data)
83+
84+
s.close()
85+
return response
86+
except Exception as e:
87+
rospy.loginfo("Exception {}".format(e))

src/ros_tcp_endpoint/unity_service.py

Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
# Copyright 2020 Unity Technologies
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import rospy
16+
import socket
17+
18+
from .communication import RosReceiver
19+
from .client import ClientThread
20+
21+
22+
class UnityService(RosReceiver):
23+
"""
24+
Class to register a ROS service that's implemented in Unity.
25+
"""
26+
def __init__(self, topic, service_class, tcp_server, queue_size=10):
27+
"""
28+
29+
Args:
30+
topic: Topic name to publish messages to
31+
service_class: The message class in catkin workspace
32+
queue_size: Max number of entries to maintain in an outgoing queue
33+
"""
34+
self.topic = topic
35+
self.node_name = "{}_service".format(topic)
36+
self.service_class = service_class
37+
self.tcp_server = tcp_server
38+
self.queue_size = queue_size
39+
40+
# Start Subscriber listener function
41+
self.service = rospy.Service(self.topic, self.service_class, self.send)
42+
43+
def send(self, data):
44+
"""
45+
Connect to TCP endpoint on client, pass along message and get reply
46+
Args:
47+
data: message data to send outside of ROS network
48+
49+
Returns:
50+
The response message
51+
"""
52+
return self.tcp_server.send_unity_service(self.topic, self.service_class, data)
53+
54+
def unregister(self):
55+
"""
56+
57+
Returns:
58+
59+
"""
60+
self.service.unregister()

0 commit comments

Comments
 (0)