ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
4

[ROS2] creating integration tests for python nodes

asked 2020-07-01 04:28:15 -0500

lmiller gravatar image

updated 2020-07-02 04:03:47 -0500

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

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2021-07-25 12:09:19 -0500

RobotDreams gravatar image

I too am at the point of needing an automated test for a complex node. Here is what I plan to try in my test node:

  • use rclpy.get_node_names_and_namespaces() to be sure node is running (and to get the namespace for subsequent calls)

  • use rclpy.get_publisher_names_and_types_by_node(node_name, node_namespace) to verify node is publishing expected topics.

  • use rclpy.get_subscriber_names_and_types_by_node(node_name, node_namespace) to verify node is subscribed to expected topics.

  • Establish a publisher for each node subscriber, and a subscriber for each node publisher

  • Publish a topic to cause the node to act, then watch appropriate subscriber to verify the node acted correctly - e.g. send /cmd_vel with angular rate, and check /MotorStatus which will list "speed" of each wheel.

My node does not have parameters yet but there are calls for that.

Check https://docs.ros2.org/latest/api/rclp... for what is possible.

edit flag offensive delete link more
3

answered 2020-07-30 01:10:35 -0500

lmiller gravatar image

Tutorials and documentation are not ready yet. In the ROSCon presentation from Jacob Perron from February 2020 can be found a little example (slides 16-21) In the launch_ros Repo can be found a little talker_listener example to

edit flag offensive delete link more

Question Tools

5 followers

Stats

Asked: 2020-07-01 04:28:15 -0500

Seen: 3,196 times

Last updated: Jul 25 '21