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

Add node defined in python to launch description

asked 2021-05-05 05:42:36 -0500

fredBeauj gravatar image

updated 2021-05-06 04:55:23 -0500

I want to create a simple publisher to be used in an integration test based on launch_testing. All the examples I can find show how to launch a node defined in C++ in some package. But how I can add an instance of a subclass of rclpy.node.Node to a launch description? Here is what this could look like, following the minimal pub/sub tutorial in python:

from launch import LaunchDescription
import launch_ros
import launch_testing


import rclpy
from std_msgs.msg import String

class MinimalPublisher(Node):
    def __init__(self):
        super().__init__('minimal_publisher')
        self._publisher = self.create_publisher(String, 'tracked_objects', 10)
        timer_period = 1 # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)
        self.i = 0

    def timer_callback(self):
        msg = String()
        msg.data = f'Hello World: {self.i}'
        self._publisher.publish(msg)
        self.get_logger().info(f'Publishing: "{msg.data}"')
        self.i += 1

@pytest.mark.launch_test
def generate_test_description():
     publisher_node = MinimalPublisher()

    ####
    # how to add `publisher_node` to launch description?  The following does not work because the rclpy.node.Node type is different from launch_ros.actions.Node
    #####
    return LaunchDescription([publisher_node, launch_testing.actions.ReadyToTest()])

Workaround

I put the node definition into its own executable. This means it's more cumbersome to pass arguments to its constructor and one can't call any methods directly from a test. But for the simple example above, it's not a real limitation:

#!/bin/env python3

import rclpy
from rclpy.node import Node

class MinimalPublisher(Node):
    # implement

def main(args=None):
    rclpy.init(args=args)

    minimal_publisher = MinimalPublisher()

    rclpy.spin(minimal_publisher)

    # Destroy the node explicitly
    # (optional - otherwise it will be done automatically
    # when the garbage collector destroys the node object)
    minimal_publisher.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

And lauch it with ExecuteProcess

@pytest.mark.launch_test  
def generate_test_description():
  publisher_node = launch.actions.ExecuteProcess(
    cmd=['python3', 'publisher_node.py'],
    cwd=os.path.join(get_package_share_directory('some_pkg'), 'test/'))
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-05-05 09:54:18 -0500

updated 2021-05-05 09:55:58 -0500

Short answer: I don't think that can work, because launch_ros.actions.Nodeis really just an easy way to find & run the corresponding executable: https://github.com/ros2/launch_ros/bl...

You might be able to use launch.actions.ExecuteProcess directly if you somehow manage to provide your Python code as a one-line command (e.g. launch.actions.ExecuteProcess(cmd='python3 -c "..."', ...)), but that's probably not recommended.

edit flag offensive delete link more

Comments

I had chosen that path, too. Added it as a workaround. Thanks for the tip.

fredBeauj gravatar image fredBeauj  ( 2021-05-06 04:55:56 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-05-05 05:42:36 -0500

Seen: 389 times

Last updated: May 06 '21