Skip to content

Commit 715a402

Browse files
Merge pull request #95 from Unity-Technologies/dev
Version 0.6.0
2 parents f978d94 + 5ea9b7b commit 715a402

File tree

8 files changed

+108
-67
lines changed

8 files changed

+108
-67
lines changed

.github/workflows/stale.yaml

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
name: 'Stale issue handler'
2+
on:
3+
workflow_dispatch:
4+
schedule:
5+
- cron: '0 17 * * *' # 17:00 UTC; 10:00 PDT
6+
7+
permissions:
8+
issues: write
9+
10+
jobs:
11+
stale:
12+
runs-on: ubuntu-latest
13+
steps:
14+
- uses: actions/stale@v4.0.0
15+
id: stale
16+
with:
17+
stale-issue-label: 'stale'
18+
stale-issue-message: 'This issue has been marked stale because it has been open for 14 days with no activity. Please remove the stale label or comment on this issue, or the issue will be automatically closed in the next 14 days.'
19+
days-before-stale: 14
20+
days-before-pr-stale: -1
21+
days-before-close: 14
22+
days-before-pr-close: -1
23+
exempt-issue-labels: 'blocked,must,should,keep,pinned,work-in-progress,request,announcement'
24+
close-issue-message: 'This issue has been marked stale for 14 days and will now be closed. If this issue is still valid, please ping a maintainer.'
25+
- name: Print outputs
26+
run: echo ${{ join(steps.stale.outputs.*, ',') }}
27+

.yamato/yamato-config.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
name: Endpoint Unit Tests
22
agent:
33
type: Unity::VM
4-
image: robotics/ci-ubuntu20:latest
4+
image: robotics/ci-ubuntu20:v0.1.0-795910
55
flavor: i1.large
66
commands:
77
# run unit tests and save test results in /home/bokken/build/output/Unity-Technologies/ROS-TCP-Endpoint

CHANGELOG.md

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,26 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0/) a
2020

2121
### Fixed
2222

23+
## [0.6.0] - 2021-09-30
24+
25+
Add the [Close Stale Issues](https://github.com/marketplace/actions/close-stale-issues) action
26+
27+
### Upgrade Notes
28+
29+
### Known Issues
30+
31+
### Added
32+
33+
Support for queue_size and latch for publishers. (https://github.com/Unity-Technologies/ROS-TCP-Endpoint/issues/82)
34+
35+
### Changed
36+
37+
### Deprecated
38+
39+
### Removed
40+
41+
### Fixed
42+
2343
## [0.5.0] - 2021-07-15
2444

2545
### Upgrade Notes
@@ -56,6 +76,8 @@ Add linter, unit tests, and test coverage reporting
5676

5777
### Changed
5878

79+
Improving the performance of the read_message in client.py, This is done by receiving the entire message all at once instead of reading 1024 byte chunks and stitching them together as you go.
80+
5981
### Deprecated
6082

6183
### Removed

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.5.0</version>
4+
<version>0.6.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/client.py

Lines changed: 16 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,9 @@ def __init__(self, conn, tcp_server, incoming_ip, incoming_port):
3434
Set class variables
3535
Args:
3636
conn:
37-
source_destination_dict: dictionary of destination name to RosCommunicator class
37+
tcp_server: server object
38+
incoming_ip: connected from this IP address
39+
incoming_port: connected from this port
3840
"""
3941
self.conn = conn
4042
self.tcp_server = tcp_server
@@ -97,16 +99,7 @@ def read_message(conn):
9799
destination = ClientThread.read_string(conn)
98100
full_message_size = ClientThread.read_int32(conn)
99101

100-
while len(data) < full_message_size:
101-
# Only grabs max of 1024 bytes TODO: change to TCPServer's buffer_size
102-
grab = 1024 if full_message_size - len(data) > 1024 else full_message_size - len(data)
103-
packet = ClientThread.recvall(conn, grab)
104-
105-
if not packet:
106-
rospy.logerr("No packets...")
107-
break
108-
109-
data += packet
102+
data = ClientThread.recvall(conn, full_message_size)
110103

111104
if full_message_size > 0 and not data:
112105
rospy.logerr("No data for a message size of {}, breaking!".format(full_message_size))
@@ -158,16 +151,16 @@ def serialize_command(command, params):
158151
return cmd_info + json_info
159152

160153
def send_ros_service_request(self, srv_id, destination, data):
161-
if destination not in self.tcp_server.source_destination_dict.keys():
162-
error_msg = "Service destination '{}' is not registered! Known topics are: {} ".format(
163-
destination, self.tcp_server.source_destination_dict.keys()
154+
if destination not in self.tcp_server.ros_services.keys():
155+
error_msg = "Service destination '{}' is not registered! Known services are: {} ".format(
156+
destination, self.tcp_server.ros_services.keys()
164157
)
165158
self.tcp_server.send_unity_error(error_msg)
166159
rospy.logerr(error_msg)
167160
# TODO: send a response to Unity anyway?
168161
return
169162
else:
170-
ros_communicator = self.tcp_server.source_destination_dict[destination]
163+
ros_communicator = self.tcp_server.ros_services[destination]
171164
service_thread = threading.Thread(
172165
target=self.service_call_thread, args=(srv_id, destination, data, ros_communicator)
173166
)
@@ -188,8 +181,8 @@ def service_call_thread(self, srv_id, destination, data, ros_communicator):
188181

189182
def run(self):
190183
"""
191-
Read a message and determine where to send it based on the source_destination_dict
192-
and destination string. Then send the read message.
184+
Receive a message from Unity and determine where to send it based on the publishers table
185+
and topic string. Then send the read message.
193186
194187
If there is a response after sending the serialized data, assume it is a
195188
ROS service response.
@@ -208,6 +201,7 @@ def run(self):
208201
while not halt_event.is_set():
209202
destination, data = self.read_message(self.conn)
210203

204+
# Process this message that was sent from Unity
211205
if self.tcp_server.pending_srv_id is not None:
212206
# if we've been told that the next message will be a service request/response, process it as such
213207
if self.tcp_server.pending_srv_is_request:
@@ -225,12 +219,12 @@ def run(self):
225219
elif destination.startswith("__"):
226220
# handle a system command, such as registering new topics
227221
self.tcp_server.handle_syscommand(destination, data)
228-
elif destination in self.tcp_server.source_destination_dict:
229-
ros_communicator = self.tcp_server.source_destination_dict[destination]
230-
response = ros_communicator.send(data)
222+
elif destination in self.tcp_server.publishers:
223+
ros_communicator = self.tcp_server.publishers[destination]
224+
ros_communicator.send(data)
231225
else:
232-
error_msg = "Topic '{}' is not registered! Known topics are: {} ".format(
233-
destination, self.tcp_server.source_destination_dict.keys()
226+
error_msg = "Not registered to publish topic '{}'! Valid publish topics are: {} ".format(
227+
destination, self.tcp_server.publishers.keys()
234228
)
235229
self.tcp_server.send_unity_error(error_msg)
236230
rospy.logerr(error_msg)

src/ros_tcp_endpoint/publisher.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,7 @@ class RosPublisher(RosSender):
2222
Class to publish messages to a ROS topic
2323
"""
2424

25-
# TODO: surface latch functionality
26-
def __init__(self, topic, message_class, queue_size=10):
25+
def __init__(self, topic, message_class, queue_size=10, latch=False):
2726
"""
2827
2928
Args:
@@ -33,7 +32,7 @@ def __init__(self, topic, message_class, queue_size=10):
3332
"""
3433
RosSender.__init__(self)
3534
self.msg = message_class()
36-
self.pub = rospy.Publisher(topic, message_class, queue_size=queue_size)
35+
self.pub = rospy.Publisher(topic, message_class, queue_size=queue_size, latch=latch)
3736

3837
def send(self, data):
3938
"""

src/ros_tcp_endpoint/server.py

Lines changed: 22 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -55,16 +55,21 @@ def __init__(self, node_name, buffer_size=1024, connections=2, tcp_ip="", tcp_po
5555
self.unity_tcp_sender = UnityTcpSender()
5656

5757
self.node_name = node_name
58-
self.source_destination_dict = {}
58+
self.publishers = {}
59+
self.subscribers = {}
60+
self.ros_services = {}
61+
self.unity_services = {}
5962
self.buffer_size = buffer_size
6063
self.connections = connections
6164
self.syscommands = SysCommands(self)
6265
self.pending_srv_id = None
6366
self.pending_srv_is_request = False
6467

65-
def start(self, source_destination_dict=None):
66-
if source_destination_dict is not None:
67-
self.source_destination_dict = source_destination_dict
68+
def start(self, publishers=None, subscribers=None):
69+
if publishers is not None:
70+
self.publishers = publishers
71+
if subscribers is not None:
72+
self.subscribers = subscribers
6873
server_thread = threading.Thread(target=self.listen_loop)
6974
# Exit the server thread when the main thread terminates
7075
server_thread.daemon = True
@@ -134,14 +139,12 @@ def subscribe(self, topic, message_name):
134139

135140
rospy.loginfo("RegisterSubscriber({}, {}) OK".format(topic, message_class))
136141

137-
if topic in self.tcp_server.source_destination_dict:
138-
self.tcp_server.source_destination_dict[topic].unregister()
142+
if topic in self.tcp_server.subscribers:
143+
self.tcp_server.subscribers[topic].unregister()
139144

140-
self.tcp_server.source_destination_dict[topic] = RosSubscriber(
141-
topic, message_class, self.tcp_server
142-
)
145+
self.tcp_server.subscribers[topic] = RosSubscriber(topic, message_class, self.tcp_server)
143146

144-
def publish(self, topic, message_name):
147+
def publish(self, topic, message_name, queue_size=10, latch=False):
145148
if topic == "":
146149
self.tcp_server.send_unity_error(
147150
"Can't publish to a blank topic name! SysCommand.publish({}, {})".format(
@@ -159,12 +162,10 @@ def publish(self, topic, message_name):
159162

160163
rospy.loginfo("RegisterPublisher({}, {}) OK".format(topic, message_class))
161164

162-
if topic in self.tcp_server.source_destination_dict:
163-
self.tcp_server.source_destination_dict[topic].unregister()
165+
if topic in self.tcp_server.publishers:
166+
self.tcp_server.publishers[topic].unregister()
164167

165-
self.tcp_server.source_destination_dict[topic] = RosPublisher(
166-
topic, message_class, queue_size=10
167-
)
168+
self.tcp_server.publishers[topic] = RosPublisher(topic, message_class, queue_size, latch)
168169

169170
def ros_service(self, topic, message_name):
170171
if topic == "":
@@ -186,10 +187,10 @@ def ros_service(self, topic, message_name):
186187

187188
rospy.loginfo("RegisterRosService({}, {}) OK".format(topic, message_class))
188189

189-
if topic in self.tcp_server.source_destination_dict:
190-
self.tcp_server.source_destination_dict[topic].unregister()
190+
if topic in self.tcp_server.ros_services:
191+
self.tcp_server.ros_services[topic].unregister()
191192

192-
self.tcp_server.source_destination_dict[topic] = RosService(topic, message_class)
193+
self.tcp_server.ros_services[topic] = RosService(topic, message_class)
193194

194195
def unity_service(self, topic, message_name):
195196
if topic == "":
@@ -211,12 +212,10 @@ def unity_service(self, topic, message_name):
211212

212213
rospy.loginfo("RegisterUnityService({}, {}) OK".format(topic, message_class))
213214

214-
if topic in self.tcp_server.source_destination_dict:
215-
self.tcp_server.source_destination_dict[topic].unregister()
215+
if topic in self.tcp_server.unity_services:
216+
self.tcp_server.unity_services[topic].unregister()
216217

217-
self.tcp_server.source_destination_dict[topic] = UnityService(
218-
topic, message_class, self.tcp_server
219-
)
218+
self.tcp_server.unity_services[topic] = UnityService(topic, message_class, self.tcp_server)
220219

221220
def response(self, srv_id): # the next message is a service response
222221
self.tcp_server.pending_srv_id = srv_id

0 commit comments

Comments
 (0)