Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

using "subscriber->take()" and creating subscriber with a callback function together #2697

Open
theksg opened this issue Dec 3, 2024 · 1 comment
Labels
more-information-needed Further information is required

Comments

@theksg
Copy link

theksg commented Dec 3, 2024

Issue Description
I'm working on a ROS 2 node where I have set up a subscriber using theNode->create_subscription that invokes a callback function. This callback function is designed to call an external API whenever a message is received.

In a separate function within the same node, I am attempting to manually retrieve messages using subscriber->take(msg, msgInfo);.

Current Behavior:
When I attempt to use subscriber->take(msg, msgInfo);, it returns false.
The msg object contains only the first message that was published on the topic.
Questions:
Will this approach work as intended?
How does the interaction between the automatic callback and manual message retrieval (take) function?
Why might take be returning false and only providing the first message?
Any insights or recommendations on how to handle both message processing methods effectively would be appreciated.

Thank you!

@mjcarroll
Copy link
Member

It appears that you have several questions here, so I will try to address them separately.
The core of it seems to come from mixing the callback-based approach and retrieving the messages manually via take.

Interactions between the executor and take

When you add the node/subscription to the executor and call spin, then the incoming message queue will be serviced and your callback will be called with the message data according to your QoS. This is a push-based approach.

When you call take, you are taking the data directly from the subscription queue. This is a pull-based approach.

These two methods may "compete" for messages, especially if you are working in multiple threads.

Why does take return false

take should always return True if there was a message available in the incoming queue. If your callback has already processed all of the messages in the queue, that may be the reason that you see False.

Returning only the first message sounds very strange, I can't think of a reason that would happen, but a minimal reproducible example would be very helpful here.

My recommendations

Stick to one approach or introduce synchronization primitives (mutex, etc), to make sure that you don't have multiple things servicing the same queues.

You may also want to consider directly using the rclcpp::WaitSet if you want to do more complicated patterns in how you service available messages.

You can specifically add entities that you are interested in to the WaitSet and then do whatever processing you see fit based on which ones were ready.

There are multiple examples of how to use the waitset here: https://github.com/ros2/examples/tree/rolling/rclcpp/wait_set

@mjcarroll mjcarroll added the more-information-needed Further information is required label Dec 12, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
more-information-needed Further information is required
Projects
None yet
Development

No branches or pull requests

2 participants