Skip to content

Instantly share code, notes, and snippets.

@coreylynch
Created March 30, 2023 23:47
Show Gist options
  • Save coreylynch/296a4f15ac86aa15ea98b3826835d5bd to your computer and use it in GitHub Desktop.
Save coreylynch/296a4f15ac86aa15ea98b3826835d5bd to your computer and use it in GitHub Desktop.
import rclpy
from rclpy.node import Node
import threading
from std_msgs.msg import String
class MinimalPublisher(Node):
def __init__(self, name):
super().__init__(f'minimal_publisher_{name}')
self.publisher_ = self.create_publisher(String, 'topic', 10)
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
self.name = name
def timer_callback(self):
msg = String()
msg.data = f'Hello World {self.name}: {self.i}'
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.i += 1
class MinimalSubscriber(Node):
def __init__(self, name):
super().__init__(f'minimal_subscriber_{name}')
self.subscription = self.create_subscription(
String,
'topic',
self.listener_callback,
10)
self.subscription # prevent unused variable warning
def listener_callback(self, msg):
self.get_logger().info('I heard: "%s"' % msg.data)
def main(args=None):
rclpy.init(args=args)
rclpy.init(args=args)
print('hi1')
minimal_publisher = MinimalPublisher('pub1')
minimal_subscriber = MinimalSubscriber('sub1')
print('hi2')
minimal_publisher2 = MinimalPublisher('pub2')
minimal_subscriber2 = MinimalSubscriber('sub2')
# WORKS.
# executor = rclpy.executors.MultiThreadedExecutor()
# executor.add_node(minimal_publisher)
# executor.add_node(minimal_subscriber)
# executor.add_node(minimal_publisher2)
# executor.add_node(minimal_subscriber2)
# executor_thread = threading.Thread(target=executor.spin, daemon=True)
# executor_thread.start()
# executor_thread.join()
# This doesn't work.
executor1 = rclpy.executors.MultiThreadedExecutor()
executor2 = rclpy.executors.MultiThreadedExecutor()
executor1.add_node(minimal_publisher)
executor1.add_node(minimal_subscriber)
executor2.add_node(minimal_publisher2)
executor2.add_node(minimal_subscriber2)
executor_thread1 = threading.Thread(target=executor1.spin, daemon=True)
executor_thread1.start()
executor_thread1.join()
executor_thread2 = threading.Thread(target=executor2.spin, daemon=True)
executor_thread2.start()
executor_thread2.join()
if __name__ == '__main__':
main()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment