Skip to content

Commit 993d366

Browse files
authored
Release 0.7.0 (ROS1)
2 parents 715a402 + 004426d commit 993d366

22 files changed

+315
-174
lines changed

.github/workflows/jira-link.yaml

+22
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
name: jira-link
2+
3+
on:
4+
pull_request:
5+
types: [opened, edited, reopened, synchronize]
6+
7+
jobs:
8+
jira-link:
9+
runs-on: ubuntu-20.04
10+
steps:
11+
- name: check pull request title and source branch name
12+
run: |
13+
echo "Checking pull request with title ${{ github.event.pull_request.title }} from source branch ${{ github.event.pull_request.head.ref }}"
14+
if ! [[ "${{ github.event.pull_request.title }}" =~ ^AIRO-[0-9]+[[:space:]].*$ ]] && ! [[ "${{ github.event.pull_request.head.ref }}" =~ ^AIRO-[0-9]+.*$ ]]
15+
then
16+
echo -e "Please make sure one of the following is true:\n \
17+
1. the pull request title starts with 'AIRO-xxxx ', e.g. 'AIRO-1024 My Pull Request'\n \
18+
2. the source branch starts with 'AIRO-xxx', e.g. 'AIRO-1024-my-branch'"
19+
exit 1
20+
else
21+
echo "Completed checking"
22+
fi

.yamato/sonar.yml

+17
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
name: Sonarqube Standard Scan
2+
agent:
3+
type: Unity::metal::macmini
4+
image: package-ci/mac
5+
flavor: m1.mac
6+
variables:
7+
SONARQUBE_PROJECT_KEY: ai-robotics-endpoint-ros
8+
commands:
9+
- curl https://binaries.sonarsource.com/Distribution/sonar-scanner-cli/sonar-scanner-cli-4.6.2.2472-macosx.zip -o sonar-scanner-macosx.zip -L
10+
- unzip sonar-scanner-macosx.zip -d ~/sonar-scanner
11+
- ~/sonar-scanner/sonar-scanner-4.6.2.2472-macosx/bin/sonar-scanner -Dsonar.projectKey=$SONARQUBE_PROJECT_KEY -Dsonar.sources=. -Dsonar.host.url=$SONARQUBE_ENDPOINT_URL_PRD -Dsonar.login=$SONARQUBE_TOKEN_PRD
12+
triggers:
13+
cancel_old_ci: true
14+
expression: |
15+
((pull_request.target eq "main" OR pull_request.target eq "dev-ros")
16+
AND NOT pull_request.push.changes.all match "**/*.md") OR
17+
(push.branch eq "main" OR push.branch eq "dev-ros")

.yamato/yamato-config.yml

+8-5
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,9 @@ agent:
33
type: Unity::VM
44
image: robotics/ci-ubuntu20:v0.1.0-795910
55
flavor: i1.large
6+
variables:
7+
# Coverage measured as a percentage (out of 100)
8+
COVERAGE_EXPECTED: 30
69
commands:
710
# run unit tests and save test results in /home/bokken/build/output/Unity-Technologies/ROS-TCP-Endpoint
811
- command: |
@@ -15,14 +18,14 @@ commands:
1518
- command: |
1619
linecoverage=$(head -2 test-results/coverage.xml | grep -Eo 'line-rate="[0-9]+([.][0-9]+)?"' | grep -Eo "[0-9]+([.][0-9]+)?")
1720
echo "Line coverage: $linecoverage"
18-
if (( $(echo "$linecoverage < 0.3" | bc -l) )); then exit 1; fi
21+
if (( $(echo "$linecoverage * 100.0 < $COVERAGE_EXPECTED" | bc -l) ));
22+
then echo "ERROR: Code Coverage is under threshold of $COVERAGE_EXPECTED%" && exit 1
23+
fi
1924
triggers:
2025
cancel_old_ci: true
2126
expression: |
22-
(pull_request.target eq "main" AND
23-
NOT pull_request.push.changes.all match "**/*.md") OR
24-
(pull_request.target eq "dev" AND
25-
NOT pull_request.push.changes.all match "**/*.md")
27+
(pull_request.target eq "main" OR push.branch eq "main" OR pull_request.target eq "dev-ros" OR push.branch eq "dev-ros")
28+
AND NOT pull_request.push.changes.all match "**/*.md"
2629
artifacts:
2730
logs:
2831
paths:

CHANGELOG.md

+13
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,19 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0/) a
2020

2121
### Fixed
2222

23+
## [0.7.0] - 2022-02-01
24+
25+
### Added
26+
27+
Added Sonarqube Scanner
28+
29+
Private ros params
30+
31+
Send information during hand shaking for ros and package version checks
32+
33+
Send service response as one queue item
34+
35+
2336
## [0.6.0] - 2021-09-30
2437

2538
Add the [Close Stale Issues](https://github.com/marketplace/actions/close-stale-issues) action

README.md

+11-2
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,19 @@
11
# ROS TCP Endpoint
22

3-
[![License](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://opensource.org/licenses/Apache-2.0)
3+
[![License](https://img.shields.io/badge/license-Apache--2.0-green.svg)](LICENSE.md)
4+
[![Version](https://img.shields.io/github/v/tag/Unity-Technologies/ROS-TCP-Endpoint)](https://github.com/Unity-Technologies/ROS-TCP-Endpoint/releases)
5+
![ROS](https://img.shields.io/badge/ros-melodic,noetic-brightgreen)
6+
![ROS](https://img.shields.io/badge/ros2-foxy,galactic-brightgreen)
7+
8+
---
9+
10+
We're currently working on lots of things! Please take a short moment fill out our [survey](https://unitysoftware.co1.qualtrics.com/jfe/form/SV_0ojVkDVW0nNrHkW) to help us identify what products and packages to build next.
11+
12+
---
413

514
## Introduction
615

7-
[ROS](https://www.ros.org/) package used to create an endpoint to accept ROS messages sent from a Unity scene using the [ROS TCP Connector](https://github.com/Unity-Technologies/ROS-TCP-Connector) scripts.
16+
[ROS](https://www.ros.org/) package used to create an endpoint to accept ROS messages sent from a Unity scene. This ROS package works in tandem with the [ROS TCP Connector](https://github.com/Unity-Technologies/ROS-TCP-Connector) Unity package.
817

918
Instructions and examples on how to use this ROS package can be found on the [Unity Robotics Hub](https://github.com/Unity-Technologies/Unity-Robotics-Hub/blob/master/tutorials/ros_unity_integration/README.md) repository.
1019

config/params.yaml

-1
This file was deleted.

launch/endpoint.launch

+8-3
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,9 @@
11
<launch>
2-
<rosparam file="$(find ros_tcp_endpoint)/config/params.yaml" command="load"/>
3-
<node name="server_endpoint" pkg="ros_tcp_endpoint" type="default_server_endpoint.py" args="--wait" output="screen" respawn="true" />
4-
</launch>
2+
<arg name="tcp_ip" default="0.0.0.0"/>
3+
<arg name="tcp_port" default="10000"/>
4+
5+
<node name="unity_endpoint" pkg="ros_tcp_endpoint" type="default_server_endpoint.py" output="screen">
6+
<param name="tcp_ip" type="string" value="$(arg tcp_ip)"/>
7+
<param name="tcp_port" type="int" value="$(arg tcp_port)"/>
8+
</node>
9+
</launch>

package.xml

+1-1
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.6.0</version>
4+
<version>0.7.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/__init__.py

-4
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,4 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
from .publisher import RosPublisher
16-
from .subscriber import RosSubscriber
17-
from .service import RosService
1815
from .server import TcpServer
19-
from .unity_service import UnityService

src/ros_tcp_endpoint/client.py

+21-20
Original file line numberDiff line numberDiff line change
@@ -71,8 +71,7 @@ def read_int32(conn):
7171
num = struct.unpack("<I", raw_bytes)[0]
7272
return num
7373

74-
@staticmethod
75-
def read_string(conn):
74+
def read_string(self):
7675
"""
7776
Reads int32 from socket connection to determine how many bytes to
7877
read to get the string that follows. Read that number of bytes and
@@ -81,30 +80,32 @@ def read_string(conn):
8180
Returns: string
8281
8382
"""
84-
str_len = ClientThread.read_int32(conn)
83+
str_len = ClientThread.read_int32(self.conn)
8584

86-
str_bytes = ClientThread.recvall(conn, str_len)
85+
str_bytes = ClientThread.recvall(self.conn, str_len)
8786
decoded_str = str_bytes.decode("utf-8")
8887

8988
return decoded_str
9089

91-
@staticmethod
92-
def read_message(conn):
90+
def read_message(self, conn):
9391
"""
9492
Decode destination and full message size from socket connection.
9593
Grab bytes in chunks until full message has been read.
9694
"""
9795
data = b""
9896

99-
destination = ClientThread.read_string(conn)
97+
destination = self.read_string()
10098
full_message_size = ClientThread.read_int32(conn)
10199

102100
data = ClientThread.recvall(conn, full_message_size)
103101

104102
if full_message_size > 0 and not data:
105-
rospy.logerr("No data for a message size of {}, breaking!".format(full_message_size))
103+
self.tcp_server.logerr(
104+
"No data for a message size of {}, breaking!".format(full_message_size)
105+
)
106106
return
107107

108+
destination = destination.rstrip("\x00")
108109
return destination, data
109110

110111
@staticmethod
@@ -151,16 +152,16 @@ def serialize_command(command, params):
151152
return cmd_info + json_info
152153

153154
def send_ros_service_request(self, srv_id, destination, data):
154-
if destination not in self.tcp_server.ros_services.keys():
155+
if destination not in self.tcp_server.ros_services_table.keys():
155156
error_msg = "Service destination '{}' is not registered! Known services are: {} ".format(
156-
destination, self.tcp_server.ros_services.keys()
157+
destination, self.tcp_server.ros_services_table.keys()
157158
)
158159
self.tcp_server.send_unity_error(error_msg)
159-
rospy.logerr(error_msg)
160+
self.tcp_server.logerr(error_msg)
160161
# TODO: send a response to Unity anyway?
161162
return
162163
else:
163-
ros_communicator = self.tcp_server.ros_services[destination]
164+
ros_communicator = self.tcp_server.ros_services_table[destination]
164165
service_thread = threading.Thread(
165166
target=self.service_call_thread, args=(srv_id, destination, data, ros_communicator)
166167
)
@@ -173,7 +174,7 @@ def service_call_thread(self, srv_id, destination, data, ros_communicator):
173174
if not response:
174175
error_msg = "No response data from service '{}'!".format(destination)
175176
self.tcp_server.send_unity_error(error_msg)
176-
rospy.logerr(error_msg)
177+
self.tcp_server.logerr(error_msg)
177178
# TODO: send a response to Unity anyway?
178179
return
179180

@@ -194,7 +195,7 @@ def run(self):
194195
msg: the ROS msg type as bytes
195196
196197
"""
197-
rospy.loginfo("Connection from {}".format(self.incoming_ip))
198+
self.tcp_server.loginfo("Connection from {}".format(self.incoming_ip))
198199
halt_event = threading.Event()
199200
self.tcp_server.unity_tcp_sender.start_sender(self.conn, halt_event)
200201
try:
@@ -219,18 +220,18 @@ def run(self):
219220
elif destination.startswith("__"):
220221
# handle a system command, such as registering new topics
221222
self.tcp_server.handle_syscommand(destination, data)
222-
elif destination in self.tcp_server.publishers:
223-
ros_communicator = self.tcp_server.publishers[destination]
223+
elif destination in self.tcp_server.publishers_table:
224+
ros_communicator = self.tcp_server.publishers_table[destination]
224225
ros_communicator.send(data)
225226
else:
226227
error_msg = "Not registered to publish topic '{}'! Valid publish topics are: {} ".format(
227-
destination, self.tcp_server.publishers.keys()
228+
destination, self.tcp_server.publishers_table.keys()
228229
)
229230
self.tcp_server.send_unity_error(error_msg)
230-
rospy.logerr(error_msg)
231+
self.tcp_server.logerr(error_msg)
231232
except IOError as e:
232-
rospy.logerr("Exception: {}".format(e))
233+
self.tcp_server.logerr("Exception: {}".format(e))
233234
finally:
234235
halt_event.set()
235236
self.conn.close()
236-
rospy.loginfo("Disconnected from {}".format(self.incoming_ip))
237+
self.tcp_server.loginfo("Disconnected from {}".format(self.incoming_ip))

src/ros_tcp_endpoint/communication.py

+6-4
Original file line numberDiff line numberDiff line change
@@ -15,10 +15,11 @@
1515

1616
class RosSender:
1717
"""
18-
Base class for ROS communication where data is sent to the ROS network.
18+
Base class for ROS communication where data is sent to the ROS network.
1919
"""
2020

21-
def __init__(self):
21+
def __init__(self, node_name):
22+
self.node_name = node_name
2223
pass
2324

2425
def send(self, *args):
@@ -27,10 +28,11 @@ def send(self, *args):
2728

2829
class RosReceiver:
2930
"""
30-
Base class for ROS communication where data is being sent outside of the ROS network.
31+
Base class for ROS communication where data is being sent outside of the ROS network.
3132
"""
3233

33-
def __init__(self):
34+
def __init__(self, node_name):
35+
self.node_name = node_name
3436
pass
3537

3638
def send(self, *args):

src/ros_tcp_endpoint/default_server_endpoint.py

+3-5
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,10 @@
55
from ros_tcp_endpoint import TcpServer
66

77

8-
def main():
9-
ros_node_name = rospy.get_param("/TCP_NODE_NAME", "TCPServer")
10-
tcp_server = TcpServer(ros_node_name)
11-
8+
def main(args=None):
129
# Start the Server Endpoint
13-
rospy.init_node(ros_node_name, anonymous=True)
10+
rospy.init_node("unity_endpoint", anonymous=True)
11+
tcp_server = TcpServer(rospy.get_name())
1412
tcp_server.start()
1513
rospy.spin()
1614

src/ros_tcp_endpoint/publisher.py

+5-2
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
# limitations under the License.
1414

1515
import rospy
16-
16+
import re
1717
from .communication import RosSender
1818

1919

@@ -22,6 +22,7 @@ class RosPublisher(RosSender):
2222
Class to publish messages to a ROS topic
2323
"""
2424

25+
# TODO: surface latch functionality
2526
def __init__(self, topic, message_class, queue_size=10, latch=False):
2627
"""
2728
@@ -30,7 +31,9 @@ def __init__(self, topic, message_class, queue_size=10, latch=False):
3031
message_class: The message class in catkin workspace
3132
queue_size: Max number of entries to maintain in an outgoing queue
3233
"""
33-
RosSender.__init__(self)
34+
strippedTopic = re.sub("[^A-Za-z0-9_]+", "", topic)
35+
node_name = "{}_RosPublisher".format(strippedTopic)
36+
RosSender.__init__(self, node_name)
3437
self.msg = message_class()
3538
self.pub = rospy.Publisher(topic, message_class, queue_size=queue_size, latch=latch)
3639

0 commit comments

Comments
 (0)