diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml new file mode 100644 index 0000000..e3d6b78 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -0,0 +1,5 @@ +blank_issues_enabled: false +contact_links: + - name: Unity Robotics Forum + url: https://forum.unity.com/forums/robotics.623/ + about: Discussions and questions about Unity Robotics tools, demos, or integrations. \ No newline at end of file diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 6c88fde..051bf8a 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -16,7 +16,7 @@ Provide any relevant links here. ## Testing and Verification -Please describe the tests that you ran to verify your changes. Please also provide instructions, ROS packages, and Unity project files as appropriate so we can reproduce the test environment. +Please describe the tests that you ran to verify your changes. Please also provide instructions, ROS packages, and Unity project files as appropriate so we can reproduce the test environment. ### Test Configuration: - Unity Version: [e.g. Unity 2020.2.0f1] @@ -27,8 +27,9 @@ Please describe the tests that you ran to verify your changes. Please also provi ## Checklist - [ ] Ensured this PR is up-to-date with the `dev` branch - [ ] Created this PR to target the `dev` branch -- [ ] Followed the style guidelines as described in the [Contribution Guidelines](../CONTRIBUTING.md) +- [ ] Followed the style guidelines as described in the [Contribution Guidelines](https://github.com/Unity-Technologies/ROS-TCP-Endpoint/blob/main/CONTRIBUTING.md) - [ ] Added tests that prove my fix is effective or that my feature works +- [ ] Updated the [Changelog](https://github.com/Unity-Technologies/ROS-TCP-Endpoint/blob/dev/CHANGELOG.md) and described changes in the [Unreleased section](https://github.com/Unity-Technologies/ROS-TCP-Endpoint/blob/dev/CHANGELOG.md#unreleased) - [ ] Updated the documentation as appropriate ## Other comments \ No newline at end of file diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml new file mode 100644 index 0000000..4bb53c6 --- /dev/null +++ b/.github/workflows/pre-commit.yaml @@ -0,0 +1,14 @@ +name: pre-commit + +on: + pull_request: + +jobs: + pre-commit: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + - uses: actions/setup-python@v2 + with: + python-version: 3.7.x + - uses: pre-commit/action@v2.0.0 \ No newline at end of file diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 0000000..f27883e --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,12 @@ +repos: +- repo: https://github.com/python/black + rev: 19.3b0 + hooks: + - id: black + args: [--line-length=100] +- repo: https://github.com/pre-commit/pre-commit-hooks + rev: v3.4.0 + hooks: + - id: trailing-whitespace + name: trailing-whitespace-markdown + types: [markdown] \ No newline at end of file diff --git a/.yamato/yamato-config.yml b/.yamato/yamato-config.yml index 499cb0a..2ee6720 100644 --- a/.yamato/yamato-config.yml +++ b/.yamato/yamato-config.yml @@ -4,13 +4,26 @@ agent: image: robotics/ci-ubuntu20:latest flavor: i1.large commands: - - 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 && python3 -m pytest + # 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 + 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/ + # 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 triggers: cancel_old_ci: true expression: | (pull_request.target eq "main" AND NOT pull_request.push.changes.all match "**/*.md") OR - (push.branch eq "dev" AND - NOT push.changes.all match "**/*.md") + (pull_request.target eq "dev" AND + NOT pull_request.push.changes.all match "**/*.md") +artifacts: + logs: + paths: + - "test-results/**/*" diff --git a/CHANGELOG.md b/CHANGELOG.md new file mode 100644 index 0000000..ee0f99e --- /dev/null +++ b/CHANGELOG.md @@ -0,0 +1,47 @@ +# Changelog + +All notable changes to this repository will be documented in this file. + +The format is based on [Keep a Changelog](http://keepachangelog.com/en/1.0.0/) and this project adheres to [Semantic Versioning](http://semver.org/spec/v2.0.0.html). + +## Unreleased + +### Upgrade Notes + +### Known Issues + +### Added + +### Changed + +### Deprecated + +### Removed + +### Fixed + +## [0.4.0] - 2021-05-27 + +Note: the logs only reflects the changes from version 0.3.0 + +### Upgrade Notes + +RosConnection 2.0: maintain a single constant connection from Unity to the Endpoint. This is more efficient than opening one connection per message, and it eliminates a whole bunch of user issues caused by ROS being unable to connect to Unity due to firewalls, proxies, etc. + +### Known Issues + +### Added + +Add a link to the Robotics forum, and add a config.yml to add a link in the Github Issues page + +Add linter, unit tests, and test coverage reporting + +### Changed + +### Deprecated + +### Removed + +Remove outdated handshake references + +### Fixed \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 49479f4..3980c2f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,9 +9,15 @@ find_package(catkin REQUIRED COMPONENTS catkin_python_setup() -add_message_files(DIRECTORY msg) +add_message_files(FILES + RosUnityError.msg + RosUnitySrvMessage.msg + RosUnitySysCommand.msg +) -add_service_files(DIRECTORY srv) +add_service_files(FILES + RosUnityTopicList.srv +) generate_messages(DEPENDENCIES std_msgs) diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 0f7253f..c0d4360 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -1,7 +1,7 @@ # Contribution Guidelines -Thank you for your interest in contributing to Unity Robotics! To facilitate your -contributions, we've outlined a brief set of guidelines to ensure that your extensions +Thank you for your interest in contributing to Unity Robotics! To facilitate your +contributions, we've outlined a brief set of guidelines to ensure that your extensions can be easily integrated. ## Communication @@ -40,10 +40,10 @@ We run continuous integration on all PRs; all tests must be passing before the P All Python code should follow the [PEP 8 style guidelines](https://pep8.org/). -All C# code should follow the [Microsoft C# Coding Conventions](https://docs.microsoft.com/en-us/dotnet/csharp/programming-guide/inside-a-program/coding-conventions). -Additionally, the [Unity Coding package](https://docs.unity3d.com/Packages/com.unity.coding@0.1/manual/index.html) -can be used to format, encode, and lint your code according to the standard Unity -development conventions. Be aware that these Unity conventions will supersede the +All C# code should follow the [Microsoft C# Coding Conventions](https://docs.microsoft.com/en-us/dotnet/csharp/programming-guide/inside-a-program/coding-conventions). +Additionally, the [Unity Coding package](https://docs.unity3d.com/Packages/com.unity.coding@0.1/manual/index.html) +can be used to format, encode, and lint your code according to the standard Unity +development conventions. Be aware that these Unity conventions will supersede the Microsoft C# Coding Conventions where applicable. Please note that even if the code you are changing does not adhere to these guidelines, @@ -60,5 +60,5 @@ email us at [unity-robotics@unity3d.com](mailto:unity-robotics@unity3d.com). ## Contribution review -Once you have a change ready following the above ground rules, simply make a +Once you have a change ready following the above ground rules, simply make a pull request in GitHub. \ No newline at end of file diff --git a/README.md b/README.md index 6af6ac0..40f60cb 100644 --- a/README.md +++ b/README.md @@ -10,16 +10,17 @@ Instructions and examples on how to use this ROS package can be found on the [Un ## Community and Feedback -The Unity Robotics projects are open-source and we encourage and welcome contributions. -If you wish to contribute, be sure to review our [contribution guidelines](CONTRIBUTING.md) +The Unity Robotics projects are open-source and we encourage and welcome contributions. +If you wish to contribute, be sure to review our [contribution guidelines](CONTRIBUTING.md) and [code of conduct](CODE_OF_CONDUCT.md). ## Support -For general questions, feedback, or feature requests, connect directly with the -Robotics team at [unity-robotics@unity3d.com](mailto:unity-robotics@unity3d.com). +For questions or discussions about Unity Robotics package installations or how to best set up and integrate your robotics projects, please create a new thread on the [Unity Robotics forum](https://forum.unity.com/forums/robotics.623/) and make sure to include as much detail as possible. + +For feature requests, bugs, or other issues, please file a [GitHub issue](https://github.com/Unity-Technologies/ROS-TCP-Endpoint/issues) using the provided templates and the Robotics team will investigate as soon as possible. -For bugs or other issues, please file a GitHub issue and the Robotics team will -investigate the issue as soon as possible. +For any other questions or feedback, connect directly with the +Robotics team at [unity-robotics@unity3d.com](mailto:unity-robotics@unity3d.com). ## License [Apache License 2.0](LICENSE) \ No newline at end of file diff --git a/config/params.yaml b/config/params.yaml index 50aaa22..2508c4a 100644 --- a/config/params.yaml +++ b/config/params.yaml @@ -1 +1 @@ -ROS_IP: 127.0.0.1 \ No newline at end of file +ROS_IP: 127.0.0.1 diff --git a/msg/RosUnitySrvMessage.msg b/msg/RosUnitySrvMessage.msg new file mode 100644 index 0000000..4dba817 --- /dev/null +++ b/msg/RosUnitySrvMessage.msg @@ -0,0 +1,4 @@ +int32 srv_id +bool is_request +string topic +uint8[] payload \ No newline at end of file diff --git a/package.xml b/package.xml index 919cad9..5e715c3 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ ros_tcp_endpoint - 0.3.0 + 0.4.0 Acts as the bridge between Unity messages sent via Websocket and ROS messages. Unity Robotics diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 0000000..5ad32fb --- /dev/null +++ b/requirements.txt @@ -0,0 +1,3 @@ +black +pre-commit +pytest-cov \ No newline at end of file diff --git a/setup.py b/setup.py index 92b1f3d..dc361fb 100644 --- a/setup.py +++ b/setup.py @@ -4,8 +4,6 @@ from catkin_pkg.python_setup import generate_distutils_setup # fetch values from package.xml -setup_args = generate_distutils_setup( - packages=['ros_tcp_endpoint'], - package_dir={'': 'src'}) +setup_args = generate_distutils_setup(packages=["ros_tcp_endpoint"], package_dir={"": "src"}) setup(**setup_args) diff --git a/src/ros_tcp_endpoint/client.py b/src/ros_tcp_endpoint/client.py index c54acb0..d34b25f 100644 --- a/src/ros_tcp_endpoint/client.py +++ b/src/ros_tcp_endpoint/client.py @@ -17,16 +17,18 @@ import rospy from io import BytesIO -from threading import Thread +import threading from .exceptions import TopicOrServiceNameDoesNotExistError +from ros_tcp_endpoint.msg import RosUnitySrvMessage -class ClientThread(Thread): +class ClientThread(threading.Thread): """ Thread class to read all data from a connection and pass along the data to the desired source. """ + def __init__(self, conn, tcp_server, incoming_ip, incoming_port): """ Set class variables @@ -34,11 +36,26 @@ def __init__(self, conn, tcp_server, incoming_ip, incoming_port): conn: source_destination_dict: dictionary of destination name to RosCommunicator class """ - Thread.__init__(self) self.conn = conn self.tcp_server = tcp_server self.incoming_ip = incoming_ip self.incoming_port = incoming_port + threading.Thread.__init__(self) + + @staticmethod + def recvall(conn, size, flags=0): + """ + Receive exactly bufsize bytes from the socket. + """ + buffer = bytearray(size) + view = memoryview(buffer) + pos = 0 + while pos < size: + read = conn.recv_into(view[pos:], size - pos, flags) + if not read: + raise IOError("No more data available") + pos += read + return bytes(buffer) @staticmethod def read_int32(conn): @@ -48,14 +65,9 @@ def read_int32(conn): Returns: int """ - try: - raw_bytes = conn.recv(4) - num = struct.unpack(' 1024 else full_message_size - len(data) - packet = conn.recv(grab) + packet = ClientThread.recvall(conn, grab) if not packet: - print("No packets...") + rospy.logerr("No packets...") break data += packet if full_message_size > 0 and not data: - print("No data for a message size of {}, breaking!".format(full_message_size)) + rospy.logerr("No data for a message size of {}, breaking!".format(full_message_size)) return return destination, data @@ -120,9 +126,9 @@ def serialize_message(destination, message): Returns: serialized destination and message as a list of bytes """ - dest_bytes = destination.encode('utf-8') + dest_bytes = destination.encode("utf-8") length = len(dest_bytes) - dest_info = struct.pack(' idletimeout: - if s != None: - s.close() - - s = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - s.settimeout(self.timeout_on_connect) - s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) - s.connect((self.unity_ip, self.unity_port)) - s.settimeout(self.timeout_on_send) - - s.sendall(item) - idletimeout = time.time() + self.timeout_on_idle - break # sent ok. break the retries loop - except socket.timeout: - idletimeout = 0 # assume the connection has been closed, force a reconnect + conn.sendall(item) except Exception as e: - rospy.loginfo("Exception {}".format(e)) - idletimeout = 0 + rospy.logerr("Exception on Send {}".format(e)) + break + finally: + halt_event.set() + with self.queue_lock: + if self.queue is local_queue: + self.queue = None diff --git a/src/ros_tcp_endpoint/thread_pauser.py b/src/ros_tcp_endpoint/thread_pauser.py new file mode 100644 index 0000000..8aaae21 --- /dev/null +++ b/src/ros_tcp_endpoint/thread_pauser.py @@ -0,0 +1,16 @@ +import threading + + +class ThreadPauser: + def __init__(self): + self.condition = threading.Condition() + self.result = None + + def sleep_until_resumed(self): + with self.condition: + self.condition.wait() + + def resume_with_result(self, result): + self.result = result + with self.condition: + self.condition.notify() diff --git a/src/ros_tcp_endpoint/unity_service.py b/src/ros_tcp_endpoint/unity_service.py index 0573bb9..2a6cc34 100644 --- a/src/ros_tcp_endpoint/unity_service.py +++ b/src/ros_tcp_endpoint/unity_service.py @@ -23,6 +23,7 @@ class UnityService(RosReceiver): """ Class to register a ROS service that's implemented in Unity. """ + def __init__(self, topic, service_class, tcp_server, queue_size=10): """ @@ -57,4 +58,4 @@ def unregister(self): Returns: """ - self.service.unregister() + self.service.shutdown() diff --git a/srv/UnityHandshake.srv b/srv/UnityHandshake.srv deleted file mode 100644 index fec68ff..0000000 --- a/srv/UnityHandshake.srv +++ /dev/null @@ -1,4 +0,0 @@ -string ip -uint16 port ---- -string ip \ No newline at end of file diff --git a/test/test_client.py b/test/test_client.py new file mode 100644 index 0000000..30b847d --- /dev/null +++ b/test/test_client.py @@ -0,0 +1,49 @@ +from unittest import mock +from unittest.mock import Mock +from ros_tcp_endpoint.client import ClientThread +from ros_tcp_endpoint.server import TcpServer +import sys +import threading + + +def test_client_thread_initialization(): + tcp_server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + mock_conn = mock.Mock() + client_thread = ClientThread(mock_conn, tcp_server, "127.0.0.1", 10000) + assert client_thread.tcp_server.node_name == "test-tcp-server" + assert client_thread.incoming_ip == "127.0.0.1" + assert client_thread.incoming_port == 10000 + + +def test_recvall_should_read_bytes_exact_size(): + mock_conn = mock.Mock() + mock_conn.recv_into.return_value = 1 + result = ClientThread.recvall(mock_conn, 8) + assert result == b"\x00\x00\x00\x00\x00\x00\x00\x00" + + +@mock.patch.object(ClientThread, "recvall", return_value=b"\x01\x00\x00\x00") +def test_read_int32_should_parse_int(mock_recvall): + mock_conn = mock.Mock() + result = ClientThread.read_int32(mock_conn) + mock_recvall.assert_called_once + assert result == 1 + + +@mock.patch.object(ClientThread, "read_int32", return_value=4) +@mock.patch.object(ClientThread, "recvall", return_value=b"Hello world!") +def test_read_string_should_decode(mock_recvall, mock_read_int): + mock_conn = mock.Mock() + result = ClientThread.read_string(mock_conn) + mock_recvall.assert_called_once + mock_read_int.assert_called_once + assert result == "Hello world!" + + +@mock.patch.object(ClientThread, "read_string", return_value="__srv") +@mock.patch.object(ClientThread, "read_int32", return_value=4) +@mock.patch.object(ClientThread, "recvall", return_value=b"Hello world!") +def test_read_message_return_destination_data(mock_recvall, mock_read_int, mock_read_str): + mock_conn = mock.Mock() + result = ClientThread.read_message(mock_conn) + assert result == ("__srv", b"Hello world!") diff --git a/test/test_publisher.py b/test/test_publisher.py new file mode 100644 index 0000000..feecb79 --- /dev/null +++ b/test/test_publisher.py @@ -0,0 +1,20 @@ +from unittest import mock +from ros_tcp_endpoint.publisher import RosPublisher +import rospy + + +@mock.patch.object(rospy, "Publisher") +def test_publisher_send(mock_ros): + mock_tcp_server = mock.Mock() + publisher = RosPublisher("color", mock.Mock(), mock_tcp_server) + publisher.send("test data") + publisher.msg.deserialize.assert_called_once() + publisher.pub.publish.assert_called_once() + + +@mock.patch.object(rospy, "Publisher") +def test_publisher_unregister(mock_ros): + mock_tcp_server = mock.Mock() + publisher = RosPublisher("color", mock.Mock(), mock_tcp_server) + publisher.unregister() + publisher.pub.unregister.assert_called_once() diff --git a/test/test_ros_service.py b/test/test_ros_service.py new file mode 100644 index 0000000..50e9ff1 --- /dev/null +++ b/test/test_ros_service.py @@ -0,0 +1,18 @@ +from unittest import mock +from ros_tcp_endpoint.service import RosService +import rospy + + +@mock.patch.object(rospy, "ServiceProxy") +def test_subscriber_send(mock_ros): + ros_service = RosService("color", mock.Mock()) + service_response = ros_service.send("test data") + ros_service.srv_class.deserialize.assert_called_once() + assert service_response is not None + + +@mock.patch.object(rospy, "ServiceProxy") +def test_subscriber_unregister(mock_ros): + ros_service = RosService("color", mock.Mock()) + ros_service.unregister() + ros_service.srv.close.assert_called_once() diff --git a/test/test_server.py b/test/test_server.py new file mode 100644 index 0000000..327df00 --- /dev/null +++ b/test/test_server.py @@ -0,0 +1,168 @@ +from unittest import mock +from ros_tcp_endpoint import TcpServer +from ros_tcp_endpoint.server import SysCommands +from ros_tcp_endpoint.server import resolve_message_name +import importlib +import rospy +import sys +import ros_tcp_endpoint + + +@mock.patch("socket.socket") +@mock.patch("ros_tcp_endpoint.server.rospy") +def test_server_constructor(mock_ros, mock_socket): + mock_ros.get_param = mock.Mock(return_value="127.0.0.1") + server = TcpServer("test-tcp-server") + assert server.node_name == "test-tcp-server" + assert server.tcp_ip == "127.0.0.1" + assert server.buffer_size == 1024 + assert server.connections == 2 + + +def test_start_server(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + assert server.tcp_ip == "127.0.0.1" + assert server.tcp_port == 10000 + assert server.connections == 2 + server.start() + + +def test_unity_service_empty_topic_should_return_none(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + system_cmds = SysCommands(server) + result = system_cmds.unity_service("", "test message") + assert result is None + + +def test_unity_service_resolve_message_name_failure(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + system_cmds = SysCommands(server) + result = system_cmds.unity_service("get_pos", "unresolvable message") + assert result is None + + +@mock.patch.object(rospy, "Service") +@mock.patch.object( + ros_tcp_endpoint.server, + "resolve_message_name", + return_value="unity_interfaces.msg/RosUnitySrvMessage", +) +def test_unity_service_resolve_news_service(mock_resolve_message, mock_ros_service): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + assert server.source_destination_dict == {} + system_cmds = SysCommands(server) + result = system_cmds.unity_service("get_pos", "unity_interfaces.msg/RosUnitySrvMessage") + mock_ros_service.assert_called_once + assert result is None + + +@mock.patch.object(rospy, "Service") +@mock.patch.object( + ros_tcp_endpoint.server, + "resolve_message_name", + return_value="unity_interfaces.msg/RosUnitySrvMessage", +) +def test_unity_service_resolve_existing_service(mock_resolve_message, mock_ros_service): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + server.source_destination_dict = {"get_pos": mock.Mock()} + system_cmds = SysCommands(server) + result = system_cmds.unity_service("get_pos", "unity_interfaces.msg/RosUnitySrvMessage") + mock_ros_service.assert_called_once + assert result is None + + +@mock.patch.object(sys, "modules", return_value="unity_interfaces.msg") +@mock.patch.object(importlib, "import_module") +def test_resolve_message_name(mock_import_module, mock_sys_modules): + msg_name = "unity_interfaces.msg/UnityColor.msg" + result = resolve_message_name(msg_name) + mock_import_module.assert_called_once + mock_sys_modules.assert_called_once + assert result is not None + + +def test_publish_empty_topic_should_return_none(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).publish("", "pos") + assert result is None + assert server.source_destination_dict == {} + + +def test_publish_empty_message_should_return_none(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).publish("test-topic", "") + assert result is None + assert server.source_destination_dict == {} + + +# TODO: Add publisher tests + + +@mock.patch.object(rospy, "Subscriber") +@mock.patch.object( + ros_tcp_endpoint.server, "resolve_message_name", return_value="unity_interfaces.msg/Pos" +) +def test_subscribe_to_new_topic(mock_resolve_msg, mock_ros_subscriber): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).subscribe("object_pos_topic", "pos") + assert server.source_destination_dict != {} + mock_ros_subscriber.assert_called_once + + +@mock.patch.object(rospy, "Subscriber") +@mock.patch.object( + ros_tcp_endpoint.server, "resolve_message_name", return_value="unity_interfaces.msg/Pos" +) +def test_subscribe_to_existing_topic(mock_resolve_msg, mock_ros_subscriber): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + server.source_destination_dict = {"object_pos_topic": mock.Mock()} + result = SysCommands(server).subscribe("object_pos_topic", "pos") + assert server.source_destination_dict["object_pos_topic"] is not None + mock_ros_subscriber.assert_called_once + + +def test_subscribe_to_empty_topic_should_return_none(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).subscribe("", "pos") + assert result is None + assert server.source_destination_dict == {} + + +def test_subscribe_to_empty_message_should_return_none(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).subscribe("test-topic", "") + assert result is None + assert server.source_destination_dict == {} + + +@mock.patch.object(rospy, "ServiceProxy") +@mock.patch.object(ros_tcp_endpoint.server, "resolve_message_name") +def test_ros_service_new_topic(mock_resolve_msg, mock_ros_service): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).ros_service("object_pos_topic", "pos") + assert server.source_destination_dict != {} + mock_ros_service.assert_called_once + + +@mock.patch.object(rospy, "ServiceProxy") +@mock.patch.object(ros_tcp_endpoint.server, "resolve_message_name") +def test_ros_service_existing_topic(mock_resolve_msg, mock_ros_service): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + server.source_destination_dict = {"object_pos_topic": mock.Mock()} + result = SysCommands(server).ros_service("object_pos_topic", "pos") + assert server.source_destination_dict["object_pos_topic"] is not None + mock_ros_service.assert_called_once + + +def test_ros_service_empty_topic_should_return_none(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).ros_service("", "pos") + assert result is None + assert server.source_destination_dict == {} + + +def test_ros_service_empty_message_should_return_none(): + server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000) + result = SysCommands(server).ros_service("test-topic", "") + assert result is None + assert server.source_destination_dict == {} diff --git a/test/test_smoke.py b/test/test_smoke.py deleted file mode 100644 index 095fd17..0000000 --- a/test/test_smoke.py +++ /dev/null @@ -1,23 +0,0 @@ -import pytest -from unittest import mock -import ros_tcp_endpoint - -@mock.patch('ros_tcp_endpoint.publisher.rospy') -def test_pub_constructor(mock_pub_rospy): - mock_msg_pub = mock.Mock() - pub = ros_tcp_endpoint.RosPublisher("/fake_topic", mock_msg_pub) - # Message is constructed in publisher, stored as object instance - mock_msg_pub.assert_called_once() - -@mock.patch('ros_tcp_endpoint.subscriber.rospy') -def test_sub_constructor(mock_sub_rospy): - mock_msg_sub = mock.Mock() - sub = ros_tcp_endpoint.RosSubscriber("/fake_topic2", mock_msg_sub, None) - # Message is NOT constructed in subscriber, stored as class reference - mock_msg_sub.assert_not_called() - -@mock.patch('ros_tcp_endpoint.service.rospy') -def test_srv_constructor(mock_srv_rospy): - mock_srv = mock.Mock() - src = ros_tcp_endpoint.RosService("fake_service", mock_srv) - mock_srv._request_class.assert_called_once() diff --git a/test/test_subscriber.py b/test/test_subscriber.py new file mode 100644 index 0000000..18822b9 --- /dev/null +++ b/test/test_subscriber.py @@ -0,0 +1,21 @@ +from unittest import mock +from ros_tcp_endpoint.subscriber import RosSubscriber +import rospy + + +@mock.patch.object(rospy, "Subscriber") +def test_subscriber_send(mock_ros): + mock_tcp_server = mock.Mock() + subscriber = RosSubscriber("color", mock.Mock(), mock_tcp_server) + assert subscriber.node_name == "color_subscriber" + subscriber.send("test data") + mock_tcp_server.send_unity_message.assert_called_once() + + +@mock.patch.object(rospy, "Subscriber") +def test_subscriber_unregister(mock_ros): + mock_tcp_server = mock.Mock() + subscriber = RosSubscriber("color", mock.Mock(), mock_tcp_server) + assert subscriber.node_name == "color_subscriber" + subscriber.unregister() + subscriber.sub.unregister.assert_called_once() diff --git a/test/test_tcp_sender.py b/test/test_tcp_sender.py new file mode 100644 index 0000000..3a2061e --- /dev/null +++ b/test/test_tcp_sender.py @@ -0,0 +1,57 @@ +import queue +import socket +from unittest import mock +import ros_tcp_endpoint + + +@mock.patch("ros_tcp_endpoint.tcp_sender.rospy") +def test_tcp_sender_constructor(mock_ros): + tcp_sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender() + assert tcp_sender.sender_id == 1 + assert tcp_sender.time_between_halt_checks == 5 + assert tcp_sender.queue == None + assert tcp_sender.next_srv_id == 1001 + assert tcp_sender.srv_lock != None + assert tcp_sender.services_waiting == {} + + +@mock.patch("socket.socket") +@mock.patch.object(ros_tcp_endpoint.client.ClientThread, "serialize_message") +def test_send_unity_error_should_send_msg(mock_serialize_msg, mock_socket): + sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender() + sender.send_unity_error("Test error") + mock_serialize_msg.assert_called_once() + + +@mock.patch.object(ros_tcp_endpoint.client.ClientThread, "serialize_message") +def test_send_message_should_serialize_message(mock_serialize_msg): + sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender() + sender.send_unity_message("test topic", "test msg") + mock_serialize_msg.assert_called_once() + + +@mock.patch.object(ros_tcp_endpoint.thread_pauser.ThreadPauser, "sleep_until_resumed") +@mock.patch.object(ros_tcp_endpoint.client.ClientThread, "serialize_message") +def test_send_unity_service_should_serialize_ros_unity_srv(mock_serialize_msg, mock_thread_pauser): + sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender() + sender.send_unity_service(mock.Mock(), mock.Mock(), mock.Mock()) + mock_serialize_msg.assert_called_once() + # TODO: Test the scenario when the queue is not None + assert sender.queue == None + + +@mock.patch("ros_tcp_endpoint.thread_pauser.ThreadPauser") +def test_send_unity_service_response_should_resume(mock_thread_pauser_class): + sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender() + thread_pauser = mock_thread_pauser_class() + sender.services_waiting = {"moveit": thread_pauser} + sender.send_unity_service_response("moveit", "test data") + thread_pauser.resume_with_result.assert_called_once() + + +def test_start_sender_should_increase_sender_id(): + sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender() + init_sender_id = 1 + assert sender.sender_id == init_sender_id + sender.start_sender(mock.Mock(), mock.Mock()) + assert sender.sender_id == init_sender_id + 1 diff --git a/test/test_thread_pauser.py b/test/test_thread_pauser.py new file mode 100644 index 0000000..38d786e --- /dev/null +++ b/test/test_thread_pauser.py @@ -0,0 +1,17 @@ +import threading +from unittest import mock +from ros_tcp_endpoint.thread_pauser import ThreadPauser + + +@mock.patch.object(threading.Condition, "wait") +def test_sleep_until_resumed(mock_thread_wait): + thread_pauser = ThreadPauser() + thread_pauser.sleep_until_resumed() + mock_thread_wait.assert_called_once + + +@mock.patch.object(threading.Condition, "notify") +def test_resume(mock_thread_notify): + thread_pauser = ThreadPauser() + thread_pauser.resume_with_result(mock.Mock) + mock_thread_notify.assert_called_once diff --git a/test/test_unity_service.py b/test/test_unity_service.py new file mode 100644 index 0000000..6b847bf --- /dev/null +++ b/test/test_unity_service.py @@ -0,0 +1,21 @@ +from unittest import mock +from ros_tcp_endpoint.unity_service import UnityService +import rospy + + +@mock.patch.object(rospy, "Service") +def test_unity_service_send(mock_ros_service): + mock_tcp_server = mock.Mock() + unity_service = UnityService("color", mock.Mock(), mock_tcp_server) + assert unity_service.node_name == "color_service" + unity_service.send("test data") + mock_tcp_server.send_unity_service.assert_called_once() + + +@mock.patch.object(rospy, "Service") +def test_unity_service_unregister(mock_ros_service): + mock_tcp_server = mock.Mock() + unity_service = UnityService("color", mock.Mock(), mock_tcp_server) + assert unity_service.node_name == "color_service" + unity_service.unregister() + unity_service.service.shutdown.assert_called_once()