Skip to content

Commit

Permalink
Release 0.7.0 (ROS1)
Browse files Browse the repository at this point in the history
  • Loading branch information
hyounesy authored Feb 1, 2022
2 parents 715a402 + 004426d commit 993d366
Show file tree
Hide file tree
Showing 22 changed files with 315 additions and 174 deletions.
22 changes: 22 additions & 0 deletions .github/workflows/jira-link.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
name: jira-link

on:
pull_request:
types: [opened, edited, reopened, synchronize]

jobs:
jira-link:
runs-on: ubuntu-20.04
steps:
- name: check pull request title and source branch name
run: |
echo "Checking pull request with title ${{ github.event.pull_request.title }} from source branch ${{ github.event.pull_request.head.ref }}"
if ! [[ "${{ github.event.pull_request.title }}" =~ ^AIRO-[0-9]+[[:space:]].*$ ]] && ! [[ "${{ github.event.pull_request.head.ref }}" =~ ^AIRO-[0-9]+.*$ ]]
then
echo -e "Please make sure one of the following is true:\n \
1. the pull request title starts with 'AIRO-xxxx ', e.g. 'AIRO-1024 My Pull Request'\n \
2. the source branch starts with 'AIRO-xxx', e.g. 'AIRO-1024-my-branch'"
exit 1
else
echo "Completed checking"
fi
17 changes: 17 additions & 0 deletions .yamato/sonar.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
name: Sonarqube Standard Scan
agent:
type: Unity::metal::macmini
image: package-ci/mac
flavor: m1.mac
variables:
SONARQUBE_PROJECT_KEY: ai-robotics-endpoint-ros
commands:
- curl https://binaries.sonarsource.com/Distribution/sonar-scanner-cli/sonar-scanner-cli-4.6.2.2472-macosx.zip -o sonar-scanner-macosx.zip -L
- unzip sonar-scanner-macosx.zip -d ~/sonar-scanner
- ~/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
triggers:
cancel_old_ci: true
expression: |
((pull_request.target eq "main" OR pull_request.target eq "dev-ros")
AND NOT pull_request.push.changes.all match "**/*.md") OR
(push.branch eq "main" OR push.branch eq "dev-ros")
13 changes: 8 additions & 5 deletions .yamato/yamato-config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,9 @@ agent:
type: Unity::VM
image: robotics/ci-ubuntu20:v0.1.0-795910
flavor: i1.large
variables:
# Coverage measured as a percentage (out of 100)
COVERAGE_EXPECTED: 30
commands:
# run unit tests and save test results in /home/bokken/build/output/Unity-Technologies/ROS-TCP-Endpoint
- command: |
Expand All @@ -15,14 +18,14 @@ commands:
- command: |
linecoverage=$(head -2 test-results/coverage.xml | grep -Eo 'line-rate="[0-9]+([.][0-9]+)?"' | grep -Eo "[0-9]+([.][0-9]+)?")
echo "Line coverage: $linecoverage"
if (( $(echo "$linecoverage < 0.3" | bc -l) )); then exit 1; fi
if (( $(echo "$linecoverage * 100.0 < $COVERAGE_EXPECTED" | bc -l) ));
then echo "ERROR: Code Coverage is under threshold of $COVERAGE_EXPECTED%" && exit 1
fi
triggers:
cancel_old_ci: true
expression: |
(pull_request.target eq "main" AND
NOT pull_request.push.changes.all match "**/*.md") OR
(pull_request.target eq "dev" AND
NOT pull_request.push.changes.all match "**/*.md")
(pull_request.target eq "main" OR push.branch eq "main" OR pull_request.target eq "dev-ros" OR push.branch eq "dev-ros")
AND NOT pull_request.push.changes.all match "**/*.md"
artifacts:
logs:
paths:
Expand Down
13 changes: 13 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,19 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0/) a

### Fixed

## [0.7.0] - 2022-02-01

### Added

Added Sonarqube Scanner

Private ros params

Send information during hand shaking for ros and package version checks

Send service response as one queue item


## [0.6.0] - 2021-09-30

Add the [Close Stale Issues](https://github.com/marketplace/actions/close-stale-issues) action
Expand Down
13 changes: 11 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,19 @@
# ROS TCP Endpoint

[![License](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://opensource.org/licenses/Apache-2.0)
[![License](https://img.shields.io/badge/license-Apache--2.0-green.svg)](LICENSE.md)
[![Version](https://img.shields.io/github/v/tag/Unity-Technologies/ROS-TCP-Endpoint)](https://github.com/Unity-Technologies/ROS-TCP-Endpoint/releases)
![ROS](https://img.shields.io/badge/ros-melodic,noetic-brightgreen)
![ROS](https://img.shields.io/badge/ros2-foxy,galactic-brightgreen)

---

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.

---

## Introduction

[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.
[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.

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.

Expand Down
1 change: 0 additions & 1 deletion config/params.yaml

This file was deleted.

11 changes: 8 additions & 3 deletions launch/endpoint.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,9 @@
<launch>
<rosparam file="$(find ros_tcp_endpoint)/config/params.yaml" command="load"/>
<node name="server_endpoint" pkg="ros_tcp_endpoint" type="default_server_endpoint.py" args="--wait" output="screen" respawn="true" />
</launch>
<arg name="tcp_ip" default="0.0.0.0"/>
<arg name="tcp_port" default="10000"/>

<node name="unity_endpoint" pkg="ros_tcp_endpoint" type="default_server_endpoint.py" output="screen">
<param name="tcp_ip" type="string" value="$(arg tcp_ip)"/>
<param name="tcp_port" type="int" value="$(arg tcp_port)"/>
</node>
</launch>
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>ros_tcp_endpoint</name>
<version>0.6.0</version>
<version>0.7.0</version>
<description>Acts as the bridge between Unity messages sent via Websocket and ROS messages.</description>

<maintainer email="[email protected]">Unity Robotics</maintainer>
Expand Down
4 changes: 0 additions & 4 deletions src/ros_tcp_endpoint/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,4 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from .publisher import RosPublisher
from .subscriber import RosSubscriber
from .service import RosService
from .server import TcpServer
from .unity_service import UnityService
41 changes: 21 additions & 20 deletions src/ros_tcp_endpoint/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,7 @@ def read_int32(conn):
num = struct.unpack("<I", raw_bytes)[0]
return num

@staticmethod
def read_string(conn):
def read_string(self):
"""
Reads int32 from socket connection to determine how many bytes to
read to get the string that follows. Read that number of bytes and
Expand All @@ -81,30 +80,32 @@ def read_string(conn):
Returns: string
"""
str_len = ClientThread.read_int32(conn)
str_len = ClientThread.read_int32(self.conn)

str_bytes = ClientThread.recvall(conn, str_len)
str_bytes = ClientThread.recvall(self.conn, str_len)
decoded_str = str_bytes.decode("utf-8")

return decoded_str

@staticmethod
def read_message(conn):
def read_message(self, conn):
"""
Decode destination and full message size from socket connection.
Grab bytes in chunks until full message has been read.
"""
data = b""

destination = ClientThread.read_string(conn)
destination = self.read_string()
full_message_size = ClientThread.read_int32(conn)

data = ClientThread.recvall(conn, full_message_size)

if full_message_size > 0 and not data:
rospy.logerr("No data for a message size of {}, breaking!".format(full_message_size))
self.tcp_server.logerr(
"No data for a message size of {}, breaking!".format(full_message_size)
)
return

destination = destination.rstrip("\x00")
return destination, data

@staticmethod
Expand Down Expand Up @@ -151,16 +152,16 @@ def serialize_command(command, params):
return cmd_info + json_info

def send_ros_service_request(self, srv_id, destination, data):
if destination not in self.tcp_server.ros_services.keys():
if destination not in self.tcp_server.ros_services_table.keys():
error_msg = "Service destination '{}' is not registered! Known services are: {} ".format(
destination, self.tcp_server.ros_services.keys()
destination, self.tcp_server.ros_services_table.keys()
)
self.tcp_server.send_unity_error(error_msg)
rospy.logerr(error_msg)
self.tcp_server.logerr(error_msg)
# TODO: send a response to Unity anyway?
return
else:
ros_communicator = self.tcp_server.ros_services[destination]
ros_communicator = self.tcp_server.ros_services_table[destination]
service_thread = threading.Thread(
target=self.service_call_thread, args=(srv_id, destination, data, ros_communicator)
)
Expand All @@ -173,7 +174,7 @@ def service_call_thread(self, srv_id, destination, data, ros_communicator):
if not response:
error_msg = "No response data from service '{}'!".format(destination)
self.tcp_server.send_unity_error(error_msg)
rospy.logerr(error_msg)
self.tcp_server.logerr(error_msg)
# TODO: send a response to Unity anyway?
return

Expand All @@ -194,7 +195,7 @@ def run(self):
msg: the ROS msg type as bytes
"""
rospy.loginfo("Connection from {}".format(self.incoming_ip))
self.tcp_server.loginfo("Connection from {}".format(self.incoming_ip))
halt_event = threading.Event()
self.tcp_server.unity_tcp_sender.start_sender(self.conn, halt_event)
try:
Expand All @@ -219,18 +220,18 @@ def run(self):
elif destination.startswith("__"):
# handle a system command, such as registering new topics
self.tcp_server.handle_syscommand(destination, data)
elif destination in self.tcp_server.publishers:
ros_communicator = self.tcp_server.publishers[destination]
elif destination in self.tcp_server.publishers_table:
ros_communicator = self.tcp_server.publishers_table[destination]
ros_communicator.send(data)
else:
error_msg = "Not registered to publish topic '{}'! Valid publish topics are: {} ".format(
destination, self.tcp_server.publishers.keys()
destination, self.tcp_server.publishers_table.keys()
)
self.tcp_server.send_unity_error(error_msg)
rospy.logerr(error_msg)
self.tcp_server.logerr(error_msg)
except IOError as e:
rospy.logerr("Exception: {}".format(e))
self.tcp_server.logerr("Exception: {}".format(e))
finally:
halt_event.set()
self.conn.close()
rospy.loginfo("Disconnected from {}".format(self.incoming_ip))
self.tcp_server.loginfo("Disconnected from {}".format(self.incoming_ip))
10 changes: 6 additions & 4 deletions src/ros_tcp_endpoint/communication.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,11 @@

class RosSender:
"""
Base class for ROS communication where data is sent to the ROS network.
Base class for ROS communication where data is sent to the ROS network.
"""

def __init__(self):
def __init__(self, node_name):
self.node_name = node_name
pass

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

class RosReceiver:
"""
Base class for ROS communication where data is being sent outside of the ROS network.
Base class for ROS communication where data is being sent outside of the ROS network.
"""

def __init__(self):
def __init__(self, node_name):
self.node_name = node_name
pass

def send(self, *args):
Expand Down
8 changes: 3 additions & 5 deletions src/ros_tcp_endpoint/default_server_endpoint.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,10 @@
from ros_tcp_endpoint import TcpServer


def main():
ros_node_name = rospy.get_param("/TCP_NODE_NAME", "TCPServer")
tcp_server = TcpServer(ros_node_name)

def main(args=None):
# Start the Server Endpoint
rospy.init_node(ros_node_name, anonymous=True)
rospy.init_node("unity_endpoint", anonymous=True)
tcp_server = TcpServer(rospy.get_name())
tcp_server.start()
rospy.spin()

Expand Down
7 changes: 5 additions & 2 deletions src/ros_tcp_endpoint/publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
# limitations under the License.

import rospy

import re
from .communication import RosSender


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

# TODO: surface latch functionality
def __init__(self, topic, message_class, queue_size=10, latch=False):
"""
Expand All @@ -30,7 +31,9 @@ def __init__(self, topic, message_class, queue_size=10, latch=False):
message_class: The message class in catkin workspace
queue_size: Max number of entries to maintain in an outgoing queue
"""
RosSender.__init__(self)
strippedTopic = re.sub("[^A-Za-z0-9_]+", "", topic)
node_name = "{}_RosPublisher".format(strippedTopic)
RosSender.__init__(self, node_name)
self.msg = message_class()
self.pub = rospy.Publisher(topic, message_class, queue_size=queue_size, latch=latch)

Expand Down
Loading

0 comments on commit 993d366

Please sign in to comment.