[ROS2] creating integration tests for python nodes
I'm trying to create some tests for my nodes. I have already done simple unittests with pytest and unittest.
Now we say i have following simple node called publisher:
import rclpy
from rclpy.node import Node
from std_msgs.msg import Float64
class Publisher(Node):
def __init__(self):
super().__init__('publisher')
self.get_logger().info("Running...")
self.declare_parameter("frequency", 0.5)
self.declare_parameter("start_index", 0.0)
self._publisher = self.create_publisher(Float64, 'topic_a', 10)
frequency = self.get_parameter("frequency").get_parameter_value().double_value
self._timer_period = 1/frequency
self._timer = self.create_timer(self._timer_period, self._cb_timer)
self._i= self.get_parameter("start_index").get_parameter_value().double_value
def _cb_timer(self):
msg = Float64()
msg.data = float(self._i)
self._publisher.publish(msg)
self._i = self._i + 1
def main(args=None):
rclpy.init(args=args)
publisher = Publisher()
rclpy.spin(publisher)
publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
I want to test something like the parameters have been set correctly or the subscriber/publisher created the right topics:
I've created a unittest.Testcase class, that run with colcon test
class test_launch(unittest.TestCase):
def setUp(self):
rclpy.init()
self.test_node = rclpy.create_node("test_node")
def tearDown(self):
self.test_node.destroy_node()
rclpy.shutdown()
def test_topic_name(self):
topics = self.test_node.get_topic_names_and_types()
topic = "topic_a"
self.assertIn(topic, str(topics))
I know i have to start the node for the test, but i cannot find any way to do it for the test. How can i do that? Or is there a better way to do such tests? Tests should be done in python packages.
i found following articles and links, but I have no answer on my question
ROS2 Design -> Testing chapter is in TODO state. I only know that i have to use the launch_testing package
system_tests Repo & demo_nodes_cpp -> I think the examples are hard to understand for beginners like me. Maybe there exist an simple example or tutorial, that gives an overview of working with python nodes and node tests
I'm using Foxy on Ubuntu 20.04