Skip to content

Commit

Permalink
Release 0.7.0 (ROS2)
Browse files Browse the repository at this point in the history
  • Loading branch information
hyounesy authored Feb 1, 2022
2 parents 09d97b2 + d43d095 commit 54c1a64
Show file tree
Hide file tree
Showing 20 changed files with 196 additions and 121 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
3 changes: 2 additions & 1 deletion .github/workflows/pre-commit.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -10,4 +10,5 @@ jobs:
- uses: actions/checkout@v2
- uses: actions/setup-python@v2
with:
python-version: 3.7.x
python-version: 3.7.x

2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
.DS_Store
*.pyc
.idea
.coverage
test-results/
*~
build
devel
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-ros2
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-ros2")
AND NOT pull_request.push.changes.all match "**/*.md") OR
(push.branch eq "main" OR push.branch eq "dev-ros2")
24 changes: 14 additions & 10 deletions .yamato/yamato-config.yml
Original file line number Diff line number Diff line change
@@ -1,28 +1,32 @@
name: Endpoint Unit Tests
agent:
type: Unity::VM
image: robotics/ci-ubuntu20:v0.1.0-795910
image: robotics/ci-ros2-galactic-ubuntu20:v0.0.2-916903
flavor: i1.large
variables:
# Coverage measured as a percentage (out of 100)
COVERAGE_EXPECTED: 3.5
commands:
# run unit tests and save test results in /home/bokken/build/output/Unity-Technologies/ROS-TCP-Endpoint
- command: |
source /opt/ros/noetic/setup.bash && echo "ROS_DISTRO == $ROS_DISTRO"
cd .. && mkdir -p catkin_ws/src && cp -r ./ROS-TCP-Endpoint catkin_ws/src
cd catkin_ws && catkin_make && source devel/setup.bash
source /opt/ros/galactic/setup.bash && echo "ROS_DISTRO == galactic"
cd .. && mkdir -p ros_ws/src && cp -r ./ROS-TCP-Endpoint ros_ws/src
cd ros_ws && colcon build && source install/local_setup.bash
cd src/ROS-TCP-Endpoint
python3 -m pytest --cov=. --cov-report xml:../../../ROS-TCP-Endpoint/test-results/coverage.xml --cov-report html:../../../ROS-TCP-Endpoint/test-results/coverage.html test/
python3 -m pytest --cov=. --cov-report xml:./test-results/coverage.xml --cov-report html:./test-results/coverage.html test/
# check the test coverage
- 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-ros2" OR pull_request.target eq "dev-ros2")
AND NOT pull_request.push.changes.all match "**/*.md") OR
(push.branch eq "main-ros2" OR push.branch eq "dev-ros2")
artifacts:
logs:
paths:
Expand Down
16 changes: 15 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0/) a

### Added

Added Sonarqube scanner

### Changed

### Deprecated
Expand All @@ -20,6 +22,18 @@ 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

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 Expand Up @@ -84,4 +98,4 @@ Improving the performance of the read_message in client.py, This is done by rece

Remove outdated handshake references

### Fixed
### Fixed
22 changes: 10 additions & 12 deletions launch/endpoint.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,13 @@


def generate_launch_description():
return LaunchDescription([
Node(
package='ros_tcp_endpoint',
executable='default_server_endpoint',
emulate_tty=True,
parameters=[
{'ROS_IP': '0.0.0.0'},
{'ROS_TCP_PORT': 10000},
],
),
])

return LaunchDescription(
[
Node(
package="ros_tcp_endpoint",
executable="default_server_endpoint",
emulate_tty=True,
parameters=[{"ROS_IP": "0.0.0.0"}, {"ROS_TCP_PORT": 10000}],
)
]
)
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros_tcp_endpoint</name>
<version>0.6.0</version>
<version>0.7.0</version>
<description>ROS TCP Endpoint Unity Integration (ROS2 version)
Acts as the bridge between Unity messages sent via TCP socket and ROS messages.
</description>
Expand Down
18 changes: 6 additions & 12 deletions ros_tcp_endpoint/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ def send_ros_service_request(self, srv_id, destination, data):
destination, self.tcp_server.ros_services_table.keys()
)
self.tcp_server.send_unity_error(error_msg)
self.logerr(error_msg)
self.tcp_server.logerr(error_msg)
# TODO: send a response to Unity anyway?
return
else:
Expand All @@ -165,18 +165,12 @@ 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)
self.logerr(error_msg)
self.tcp_server.logerr(error_msg)
# TODO: send a response to Unity anyway?
return

self.tcp_server.unity_tcp_sender.send_ros_service_response(srv_id, destination, response)

def loginfo(self, text):
self.tcp_server.get_logger().info(text)

def logerr(self, text):
self.tcp_server.get_logger().error(text)

def run(self):
"""
Receive a message from Unity and determine where to send it based on the publishers table
Expand All @@ -192,7 +186,7 @@ def run(self):
msg: the ROS msg type as bytes
"""
self.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 Down Expand Up @@ -225,10 +219,10 @@ def run(self):
destination, self.tcp_server.publishers_table.keys()
)
self.tcp_server.send_unity_error(error_msg)
self.logerr(error_msg)
self.tcp_server.logerr(error_msg)
except IOError as e:
self.logerr("Exception: {}".format(e))
self.tcp_server.logerr("Exception: {}".format(e))
finally:
halt_event.set()
self.conn.close()
self.loginfo("Disconnected from {}".format(self.incoming_ip))
self.tcp_server.loginfo("Disconnected from {}".format(self.incoming_ip))
2 changes: 2 additions & 0 deletions ros_tcp_endpoint/communication.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ class RosSender(Node):
"""
Base class for ROS communication where data is sent to the ROS network.
"""

def __init__(self, node_name):
super().__init__(node_name)
pass
Expand All @@ -32,6 +33,7 @@ class RosReceiver(Node):
"""
Base class for ROS communication where data is being sent outside of the ROS network.
"""

def __init__(self, node_name):
super().__init__(node_name)
pass
Expand Down
2 changes: 1 addition & 1 deletion ros_tcp_endpoint/default_server_endpoint.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

def main(args=None):
rclpy.init(args=args)
tcp_server = TcpServer('TCPServer')
tcp_server = TcpServer("UnityEndpoint")

tcp_server.start()

Expand Down
53 changes: 28 additions & 25 deletions ros_tcp_endpoint/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,15 +52,13 @@ def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip=None, tcp
self.declare_parameter("ROS_TCP_PORT", 10000)

if tcp_ip:
self.get_logger().log("Using ROS_IP override from constructor: {}".format(tcp_ip))
self.loginfo("Using ROS_IP override from constructor: {}".format(tcp_ip))
self.tcp_ip = tcp_ip
else:
self.tcp_ip = self.get_parameter("ROS_IP").get_parameter_value().string_value

if tcp_port:
self.get_logger().log(
"Using ROS_TCP_PORT override from constructor: {}".format(tcp_port)
)
self.loginfo("Using ROS_TCP_PORT override from constructor: {}".format(tcp_port))
self.tcp_port = tcp_port
else:
self.tcp_port = self.get_parameter("ROS_TCP_PORT").get_parameter_value().integer_value
Expand Down Expand Up @@ -93,7 +91,7 @@ def listen_loop(self):
Creates and binds sockets using TCP variables then listens for incoming connections.
For each new connection a client thread will be created to handle communication.
"""
self.get_logger().info("Starting server on {}:{}".format(self.tcp_ip, self.tcp_port))
self.loginfo("Starting server on {}:{}".format(self.tcp_ip, self.tcp_port))
tcp_server = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
tcp_server.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
tcp_server.bind((self.tcp_ip, self.tcp_port))
Expand All @@ -105,7 +103,7 @@ def listen_loop(self):
(conn, (ip, port)) = tcp_server.accept()
ClientThread(conn, self, ip, port).start()
except socket.timeout as err:
self.get_logger().error("ros_tcp_endpoint.TcpServer: socket timeout")
self.logerr("ros_tcp_endpoint.TcpServer: socket timeout")

def send_unity_error(self, error):
self.unity_tcp_sender.send_unity_error(error)
Expand All @@ -128,6 +126,15 @@ def handle_syscommand(self, topic, data):
params = json.loads(message_json)
function(**params)

def loginfo(self, text):
self.get_logger().info(text)

def logwarn(self, text):
self.get_logger().warning(text)

def logerr(self, text):
self.get_logger().error(text)

def setup_executor(self):
"""
Since rclpy.spin() is a blocking call the server needed a way
Expand All @@ -136,7 +143,13 @@ def setup_executor(self):
MultiThreadedExecutor allows us to set the number of threads
needed as well as the nodes that need to be spun.
"""
num_threads = len(self.publishers_table.keys()) + len(self.subscribers_table.keys()) + len(self.ros_services_table.keys()) + len(self.unity_services_table.keys()) + 1
num_threads = (
len(self.publishers_table.keys())
+ len(self.subscribers_table.keys())
+ len(self.ros_services_table.keys())
+ len(self.unity_services_table.keys())
+ 1
)
executor = MultiThreadedExecutor(num_threads)

executor.add_node(self)
Expand Down Expand Up @@ -204,9 +217,7 @@ def subscribe(self, topic, message_name):
if self.tcp_server.executor is not None:
self.tcp_server.executor.add_node(new_subscriber)

self.tcp_server.get_logger().info(
"RegisterSubscriber({}, {}) OK".format(topic, message_class)
)
self.tcp_server.loginfo("RegisterSubscriber({}, {}) OK".format(topic, message_class))

def publish(self, topic, message_name, queue_size=10, latch=False):
if topic == "":
Expand Down Expand Up @@ -234,9 +245,7 @@ def publish(self, topic, message_name, queue_size=10, latch=False):
if self.tcp_server.executor is not None:
self.tcp_server.executor.add_node(new_publisher)

self.tcp_server.get_logger().info(
"RegisterPublisher({}, {}) OK".format(topic, message_class)
)
self.tcp_server.loginfo("RegisterPublisher({}, {}) OK".format(topic, message_class))

def ros_service(self, topic, message_name):
if topic == "":
Expand Down Expand Up @@ -265,9 +274,7 @@ def ros_service(self, topic, message_name):
if self.tcp_server.executor is not None:
self.tcp_server.executor.add_node(new_service)

self.tcp_server.get_logger().info(
"RegisterRosService({}, {}) OK".format(topic, message_class)
)
self.tcp_server.loginfo("RegisterRosService({}, {}) OK".format(topic, message_class))

def unity_service(self, topic, message_name):
if topic == "":
Expand Down Expand Up @@ -297,9 +304,7 @@ def unity_service(self, topic, message_name):
if self.tcp_server.executor is not None:
self.tcp_server.executor.add_node(new_service)

self.tcp_server.get_logger().info(
"RegisterUnityService({}, {}) OK".format(topic, message_class)
)
self.tcp_server.loginfo("RegisterUnityService({}, {}) OK".format(topic, message_class))

def response(self, srv_id): # the next message is a service response
self.tcp_server.pending_srv_id = srv_id
Expand All @@ -320,20 +325,18 @@ def resolve_message_name(self, name, extension="msg"):
importlib.import_module(module_name + "." + extension)
module = sys.modules[module_name]
if module is None:
self.tcp_server.get_logger().error(
"Failed to resolve module {}".format(module_name)
)
self.tcp_server.logerr("Failed to resolve module {}".format(module_name))
module = getattr(module, extension)
if module is None:
self.tcp_server.get_logger().error(
self.tcp_server.logerr(
"Failed to resolve module {}.{}".format(module_name, extension)
)
module = getattr(module, class_name)
if module is None:
self.tcp_server.get_logger().error(
self.tcp_server.logerr(
"Failed to resolve module {}.{}.{}".format(module_name, extension, class_name)
)
return module
except (IndexError, KeyError, AttributeError, ImportError) as e:
self.tcp_server.get_logger().error("Failed to resolve message name: {}".format(e))
self.tcp_server.logerr("Failed to resolve message name: {}".format(e))
return None
Loading

0 comments on commit 54c1a64

Please sign in to comment.