rclpy
rclpy copied to clipboard
Add SubscriptionOptions wrapper
Expose rmw_subscription_options as SubscriptionOptions.
Example usage:
import rclpy
from rclpy.node import Node
from rclpy.subscription_options import SubscriptionOptions
from std_msgs.msg import Float64
rclpy.init(args=None)
node = Node("test_sub_opts")
qos = 0
pubber_a = node.create_publisher(Float64, "test_float_a", qos)
pubber_b = node.create_publisher(Float64, "test_float_b", qos)
sub_opts = SubscriptionOptions()
sub_opts.ignore_local_publications = True
def simple_handler(msg):
print(f"Received: {msg}")
node.create_subscription(
Float64,
"test_float_a",
simple_handler,
qos,
subscription_options=sub_opts,
)
node.create_subscription(
Float64,
"test_float_b",
simple_handler,
qos,
)
for i in range(10):
a = Float64(data=1.0 * i)
b = Float64(data=2.0 * i)
pubber_a.publish(a)
pubber_b.publish(b)
rclpy.spin_once(node)
node.destroy_node()
rclpy.shutdown()
Output:
Received: std_msgs.msg.Float64(data=2.0)
Received: std_msgs.msg.Float64(data=6.0)
Received: std_msgs.msg.Float64(data=10.0)
Received: std_msgs.msg.Float64(data=14.0)
Received: std_msgs.msg.Float64(data=18.0)
@fujitatomoya I didn't find any applicable issues this was just based on a need I had for a tangential project.
I could also look at adding PublishOptions. Should I make a separate PR for that?
Just some minor comments, looks good to me !
Thanks for catching those. All sorted