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

ROS2 rclpy:Launching a child node class duplicates node

asked 2023-06-19 21:50:30 -0500

vietri22 gravatar image

ROS2 Humble on Ubuntu 22.04 I want to create a child class interface in order to simplify the creation of Nodes (especially with regards to callbackgroups and calling services from a callback). To do so, I created this child class:

import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
from rclpy.qos import QoSProfile

class ChildNode(Node):

    def __init__(self, node_name : str):
        super().__init__(node_name)
        self.srv_node = rclpy.create_node("srv_" + node_name)
        self.security_callback_group = MutuallyExclusiveCallbackGroup()

    def create_client(
        self,
        srv_type,
        srv_name: str):
        return self.srv_node.create_client(srv_type, srv_name)

    def create_security_service(
        self,
        srv_type,
        srv_name: str,
        callback):
        return self.create_service(srv_type, srv_name,callback,callback_group=self.security_callback_group)

    def spin_until_future_complete(
        self,
        future):
        rclpy.spin_until_future_complete(self.srv_node,future)

    def create_security_subscription(self, msg_type, topic: str, callback, qos_profile: QoSProfile | int):
        return super().create_subscription(msg_type, topic, callback, qos_profile, callback_group=self.security_callback_group)

    def spin(self):
        executor = MultiThreadedExecutor()
        executor.add_node(self)
        executor.spin()

Here is an example of the instance of the Child Node:

import rclpy
from example_interfaces.srv import SetBool
from msgs.srv import Trigger
from ChildNodeModule import ChildNode

class VelocityControlNode(ChildNode):

    def __init__(self):
        super().__init__('velocity_control_node')
        #Launch parameters
        self.declare_parameter('zeroPWM',1500)
        self.declare_parameter('minPWM',1100)
        self.declare_parameter('maxPWM',1900)
        self.zeroPWM = self.get_parameter('zeroPWM').get_parameter_value().integer_value
        self.minPWM = self.get_parameter('minPWM').get_parameter_value().integer_value
        self.maxPWM = self.get_parameter('maxPWM').get_parameter_value().integer_value

        # Services
        self.arm_srv = self.create_security_service(SetBool, 'arm_disarm', self.arm_disarm_cb)
        self.throttle_srv = self.create_service(SetBool, 'throttle_switch', self.throttle_switch_cb)

        #Service clients
        self.get_frame_srv = self.create_client(Trigger, 'get_frame')


def main(args=None):
    rclpy.init(args=args)
    velocity_control_node = VelocityControlNode()
    velocity_control_node.spin()
    velocity_control_node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

When trying to launch the child node from a launch file, it gives me the error:

[VelocityControlNode.py-1] [WARN] [1687227974.743260442] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.

On top of that, the __init__ function of the ChildNode class is never called.

Any guesses?

Here is the launch file for reference:

    from launch import LaunchDescription
from launch_ros.actions import Node



def generate_launch_description():
    return LaunchDescription([
        Node(
            package='control',
            executable='VelocityControlNode.py',
            name='velocity_control_node',
            parameters=[{'minPWM': 1100,
             'zeroPWM': 1500,
             'maxPWM': 1900}]
        ),
    ])
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2023-08-08 07:41:42 -0500

Mrmara gravatar image

You are remapping the name of the node if you use the name arguments:

Node(
            package='control',
            executable='VelocityControlNode.py',
            name='velocity_control_node',
            parameters=[{'minPWM': 1100,
             'zeroPWM': 1500,
             'maxPWM': 1900}]
        ),

You have two ways to solve your issue:

  1. You avoid remapping the name from the launch file

  2. When you create the child node you use of the following two arguments

2.1 cli_args: You can override the remap rules like __node or even __ns (namespace)

self.srv_node = rclpy.create_node("srv_" + node_name, cli_args=["--ros-args", "-r", "__node:=" + "srv_" + node_name]

2.2 use_global_arguments: You just avoid using global arguments, so the constructor of the node will be able to give the correct name passed as argument to the __init__

self.srv_node = rclpy.create_node("srv_" + node_name, use_global_arguments=False)

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2023-06-19 21:50:30 -0500

Seen: 380 times

Last updated: Aug 08 '23