From 9a2f4220a50207ab8f6eca9bbfbece3b185b876f Mon Sep 17 00:00:00 2001 From: irinaterebiznik Date: Tue, 17 Dec 2024 15:35:46 -0300 Subject: [PATCH 1/5] added a .gitignore file --- .gitignore | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.gitignore b/.gitignore index c18dd8d..a4df222 100644 --- a/.gitignore +++ b/.gitignore @@ -1 +1,5 @@ __pycache__/ +/inorbit_republisher/test/sample_data/build/ +/inorbit_republisher/test/sample_data/hardcodedRosbag/ +/inorbit_republisher/test/sample_data/install/ +/inorbit_republisher/test/sample_data/log/ From 4941500803b353c8e9b2ba9a95c3c8262780523b Mon Sep 17 00:00:00 2001 From: irinaterebiznik Date: Tue, 17 Dec 2024 15:36:09 -0300 Subject: [PATCH 2/5] added a .gitignore file --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index a4df222..c776db8 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,4 @@ __pycache__/ /inorbit_republisher/test/sample_data/hardcodedRosbag/ /inorbit_republisher/test/sample_data/install/ /inorbit_republisher/test/sample_data/log/ +.history/ From ae89291d1657f582b2915b81af5abbf46c46f415 Mon Sep 17 00:00:00 2001 From: irinaterebiznik Date: Fri, 20 Dec 2024 14:30:39 -0300 Subject: [PATCH 3/5] test files added to the package --- .../test/UnitTests/test_republisher.py | 36 +++++++++++++++++++ .../test/UnitTests/test_republisher.test | 9 +++++ 2 files changed, 45 insertions(+) create mode 100755 inorbit_republisher/test/UnitTests/test_republisher.py create mode 100644 inorbit_republisher/test/UnitTests/test_republisher.test diff --git a/inorbit_republisher/test/UnitTests/test_republisher.py b/inorbit_republisher/test/UnitTests/test_republisher.py new file mode 100755 index 0000000..dca1ce5 --- /dev/null +++ b/inorbit_republisher/test/UnitTests/test_republisher.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python + +import unittest +import rospy +from std_msgs.msg import String + +class TestRepublisher(unittest.TestCase): + def setUp(self): + #Inits a ROS node + rospy.init_node('test_republisher', anonymous=True) + # Sets a republisher and a subscriber node + self.test_pub = rospy.Publisher('/input_topic', String, queue_size=10) + self.received_messages = [] + # Subscribes to a specific topic + rospy.Subscriber('/output_topic', String, self.callback) + rospy.sleep(1) + + def callback(self, msg): + # Callback method to caught message in /output_topic + self.received_messages.append(msg.data) + + def test_message_republishing(self): + # Publish message in topic + test_message = "key=value" + self.test_pub.publish(String(data=test_message)) + rospy.sleep(1) + # Verify message reception + self.assertIn(test_message, self.received_messages) + + def test_no_message(self): + # Verify no message was inicially recieved + self.assertEqual(len(self.received_messages), 0) + +if __name__ == '__main__': + import rostest + rostest.rosrun('my_ros_package', 'test_republisher', TestRepublisher) diff --git a/inorbit_republisher/test/UnitTests/test_republisher.test b/inorbit_republisher/test/UnitTests/test_republisher.test new file mode 100644 index 0000000..86cb967 --- /dev/null +++ b/inorbit_republisher/test/UnitTests/test_republisher.test @@ -0,0 +1,9 @@ + + + + + + + + + From 1e91c642817d6ef072a58a7adfec99782ecb9210 Mon Sep 17 00:00:00 2001 From: irinaterebiznik Date: Mon, 23 Dec 2024 13:43:19 -0300 Subject: [PATCH 4/5] Created a unit test to test the republisher's behavior when launching. --- inorbit_republisher/config/example.yaml | 10 ++++++++++ .../test/UnitTests/test_republisher.py | 19 +++++++++++-------- .../test/UnitTests/test_republisher.test | 8 ++++---- 3 files changed, 25 insertions(+), 12 deletions(-) diff --git a/inorbit_republisher/config/example.yaml b/inorbit_republisher/config/example.yaml index 60f6c1e..646bb10 100644 --- a/inorbit_republisher/config/example.yaml +++ b/inorbit_republisher/config/example.yaml @@ -54,6 +54,16 @@ republishers: topic: "/inorbit/custom_data/0" key: "navsat" +# Añadido para los tópicos input y output +- topic: "/input_topic" + msg_type: "std_msgs/String" + mappings: + - field: "data" + mapping_type: "single_field" + out: + topic: "/output_topic" + key: "input_to_output" + static_publishers: - value_from: package_version: "rospy" diff --git a/inorbit_republisher/test/UnitTests/test_republisher.py b/inorbit_republisher/test/UnitTests/test_republisher.py index dca1ce5..c0c80fc 100755 --- a/inorbit_republisher/test/UnitTests/test_republisher.py +++ b/inorbit_republisher/test/UnitTests/test_republisher.py @@ -1,4 +1,6 @@ #!/usr/bin/env python +# Unit test for a ROS node that republishes messages from /input_topic to /output_topic. +# It uses the unittest framework and rostest for testing. import unittest import rospy @@ -6,29 +8,30 @@ class TestRepublisher(unittest.TestCase): def setUp(self): - #Inits a ROS node + # Method to set up ROS nodes used in this test. rospy.init_node('test_republisher', anonymous=True) - # Sets a republisher and a subscriber node self.test_pub = rospy.Publisher('/input_topic', String, queue_size=10) self.received_messages = [] - # Subscribes to a specific topic rospy.Subscriber('/output_topic', String, self.callback) rospy.sleep(1) def callback(self, msg): - # Callback method to caught message in /output_topic + # Method to save messages received on /output_topic. self.received_messages.append(msg.data) def test_message_republishing(self): - # Publish message in topic + # Method to send a message (key=value) to /input_topic and + # check if the republisher correctly adds the prefix (input_to_output=) and sends it to /output_topic. test_message = "key=value" + expected_message = f"input_to_output={test_message}" + rospy.loginfo(f"Publishing: {test_message} to /input_topic") self.test_pub.publish(String(data=test_message)) rospy.sleep(1) - # Verify message reception - self.assertIn(test_message, self.received_messages) + rospy.loginfo(f"Messages received: {self.received_messages}") + self.assertIn(expected_message, self.received_messages) def test_no_message(self): - # Verify no message was inicially recieved + # Method to check that self.received_messages is empty at the start of the test. self.assertEqual(len(self.received_messages), 0) if __name__ == '__main__': diff --git a/inorbit_republisher/test/UnitTests/test_republisher.test b/inorbit_republisher/test/UnitTests/test_republisher.test index 86cb967..935f749 100644 --- a/inorbit_republisher/test/UnitTests/test_republisher.test +++ b/inorbit_republisher/test/UnitTests/test_republisher.test @@ -1,9 +1,9 @@ - + - - - + + + From 4adba3cb29263c2eb6ca8dbd19eac29652ccec0a Mon Sep 17 00:00:00 2001 From: irinaterebiznik Date: Mon, 23 Dec 2024 13:51:25 -0300 Subject: [PATCH 5/5] Added a README.md file to folder --- inorbit_republisher/test/UnitTests/README.md | 31 ++++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 inorbit_republisher/test/UnitTests/README.md diff --git a/inorbit_republisher/test/UnitTests/README.md b/inorbit_republisher/test/UnitTests/README.md new file mode 100644 index 0000000..47efbeb --- /dev/null +++ b/inorbit_republisher/test/UnitTests/README.md @@ -0,0 +1,31 @@ +# Unit Test for ROS Republisher Node + +This repository contains a unit test for a ROS node that republishes messages from `/input_topic` to `/output_topic`. The test ensures the republisher node processes and republishes messages correctly. + +## Test Description + +The unit test is implemented in `test_republisher.py` and uses the `unittest` framework along with `rostest`. It includes the following test cases: + +- **`test_message_republishing`**: + - Publishes a test message (`key=value`) to `/input_topic`. + - Verifies that the republisher node republishes the message with the correct prefix (`input_to_output=`) to `/output_topic`. + +- **`test_no_message`**: + - Ensures that no messages are received on `/output_topic` at the start of the test. + +The test subscribes to `/output_topic` and collects received messages for validation. + +## Running the Unit Test + +1. **Build the Workspace**: + Ensure the workspace is built and the environment is sourced: + ```bash + cd ~/catkin_ws + rosdep install --from-paths ~/catkin_ws/src --ignore-src --rosditro=noetic + catkin clean + catkin_build inorbit_republisher --verbose +2. **Source and Run the Workspace**: + ```bash + . ~/catkin_ws/devel/setup.bash + rostest inorbit_republisher test_republisher.test + ``` \ No newline at end of file