How to use multiprocessing with Nodes in ROS2?

asked 2022-04-08 06:48:42 -0500

sinamr gravatar image

updated 2022-04-11 02:43:49 -0500

Hello ros2 experts

I am struggling to use ros2 publisher and multiprocessing. So, a simple example is as follows; I have two classes, both are children of Node. In Executor, we would like to create an instance of Publisher in a separate core (so we use multiprocessing) and then publish some values. See the following example. The problem is that the publish function is constantly called, but there is no value published over /ball_pose_marker, any suggestion?

#!/usr/bin/env python3
import time
import rclpy
import numpy as np
from rclpy.node import Node
from visualization_msgs.msg import Marker
from sensor_msgs.msg import JointState
from multiprocessing import Process


class Publisher(Node):
    def __init__(self):
        super().__init__("parent_class")
        self._ball_pub = self.create_publisher(Marker, "/ball_pose_marker", 1)
        self._ball_pose = Marker()

    def publish(self, pose):
        self._ball_pose.type = Marker.SPHERE
        self._ball_pose.action = Marker.ADD
        self._ball_pose.ns = "basic_shapes"
        self._ball_pose.id = 0
        self._ball_pose.header.frame_id = "/base"
        self._ball_pose.header.stamp = self.get_clock().now().to_msg()
        self._ball_pose.scale.x = 0.04
        self._ball_pose.scale.y = 0.04
        self._ball_pose.scale.z = 0.04
        self._ball_pose.color.r = 0.0
        self._ball_pose.color.g = 0.0
        self._ball_pose.color.b = 1.0
        self._ball_pose.color.a = 1.0
        self._ball_pose.pose.position.x = pose[0]
        self._ball_pose.pose.position.y = pose[1]
        self._ball_pose.pose.position.z = pose[2]
        self._ball_pose.pose.orientation.w = pose[3]
        self._ball_pose.pose.orientation.x = pose[4]
        self._ball_pose.pose.orientation.y = pose[5]
        self._ball_pose.pose.orientation.z = pose[6]
        self._ball_pub.publish(self._ball_pose)


class Executor(Node):
    def __init__(self):
        super().__init__("executor")

        self.joint_state_pub = self.create_publisher(JointState, "/robot/desired_joint_state", 1)
        self._joint_pose = JointState()
        self.thread_state_publisher = Process(target=self.state_publisher)
        self.thread_state_publisher.start()

    def state_publisher(self):
        visualizer = Publisher()

        while rclpy.ok():
            visualizer.publish(np.random.rand(7))

    def update(self):
        self._joint_pose.position = np.random.rand(2).tolist()
        self._joint_pose.velocity = np.random.rand(2).tolist()
        self._joint_pose.effort = np.random.rand(2).tolist()
        self.joint_state_pub.publish(self._joint_pose)


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

    executer = Executor()

    while rclpy.ok():
        rclpy.spin_once(executer, timeout_sec=0.001)
        executer.update()
        time.sleep(0.01)

    # explicitly destroy node
    rclpy.shutdown()


if __name__ == "__main__":
    main()

After checking so many combination, I just realized that even a simpler example does not work:

class Executor(Node):
    def __init__(self):
        super().__init__("executor")

        self.joint_state_pub = self.create_publisher(JointState, "/robot/desired_joint_state", 1)

        self._joint_pose = JointState()
        mp.set_start_method("fork")

        self.thread_state_publisher = Process(target=self.state_publisher)
        self.thread_state_publisher.start()

    def state_publisher(self):
        ball_pub = self.create_publisher(Marker, "/ball_pose_marker", 1)
        ball_pose = Marker()

        while rclpy.ok():
            ball_pose.type = Marker.SPHERE
            ball_pose.action = Marker.ADD
            ball_pose.ns = "basic_shapes"
            ball_pose.id = 0
            ball_pose.header.frame_id = "/base"
            ball_pose.scale.x = 0.04
            ball_pose.scale.y = 0.04
            ball_pose.scale.z = 0.04
            ball_pose.color.r = 0.0
            ball_pose.color.g = 0.0
            ball_pose.color.b = 1.0
            ball_pose.color.a = 1.0
            ball_pose.pose.position.y = 0.0
            ball_pose.pose.position.z = 0.0
            ball_pose.pose.orientation.w = 0 ...
(more)
edit retag flag offensive close merge delete