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

Add lifecycle subscriber to lifecycle nodes #2254

Open
wants to merge 2 commits into
base: rolling
Choose a base branch
from

Conversation

carmiac
Copy link

@carmiac carmiac commented Aug 1, 2023

This adds a LifecycleSubscriber class to lifecycle nodes. In general, it is a mirror of LifecyclePublisher scheme, both for determining whether to process messages and in the factory methods.

There is a linked PR that provides a demo and test node.

…ption_factory as necessary.

Signed-of-by: Adam Milner <carmiac@gmail.com>
Signed-off-by: Adam Milner <milner@elroyair.com>
Signed-off-by: Adam Milner <milner@elroyair.com>
@ros-discourse
Copy link

This pull request has been mentioned on ROS Discourse. There might be relevant details there:

https://discourse.ros.org/t/lifecycle-node-improvements/32706/1

Comment on lines +70 to +78
/// Check if we need to handle the message, and execute the callback if we do.
void handle_message(
std::shared_ptr<void> & message, const rclcpp::MessageInfo & message_info) override
{
if (!this->is_activated()) {
return;
}
rclcpp::Subscription<MessageT>::handle_message(message, message_info);
}
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

with current implementation, if the node is deactivated, all messages during that state will be ignored and dropped on the subscription because the message is already taken. i am not sure if this is the expected behavior, since application would expect that the subscription can keep the message up to the specified history depth?

CC: @ros2/team

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, this is an extremely good point; at this level, we are fetching it out of the RMW but then dropping it on the floor and not calling the user callback.

This gets into a bit of the philosophy behind the lifecycle transitions. I would expect that when a LifecycleSubscription is deactivated, then it is actually not part of the graph at all anymore, i.e. handle_message would never be called. That releases the most resources in the system, though it does have a possible side-effect of a "thundering herd" problem if a bunch of them are activated at once.

All of that said, I wasn't really involved with any of the initial concepts with the lifecycle code, so I don't fully know what the expectation is. Maybe @wjwwood could chime in here with some ideas?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We discussed this in the weekly meeting, and @wjwwood reminded me that there is a difference between the on_configure and the on_activate callbacks. Specifically, the former is when subscriptions should be created and do discovery, and the latter is when you should start receiving data. So from that perspective, this PR is actually doing the right thing by doing discovery, but not calling the callback until on_activate is called.

There is another thing to think about here, though, which is what happens with data that comes in from before a subscriber is active. Conceptually there are two ways to go here:

  1. Hold onto the data that arrives before activation, and deliver that on activation.
  2. Discard all data that arrives before activation, and only deliver new data after activation.

The design document says:

"In the inactive state, any data that arrives on managed topics will not be read and or processed. Data retention will be subject to the configured QoS policy for the topic."

That suggests to me case 1, but this PR actually implements case 2. It seems like there is a case for both of them, so personally I'd be OK with going forward with this implementation and a TODO that says implementing case 1 is future work.

@fujitatomoya @carmiac Does this all make sense to you? Thoughts?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think that this approach provides very little improvement in terms of performance.
By the time you are dropping the message, you already wasted CPU cycles to go through all the ROS and network stack and potentially copying the message multiple times.

I'm not opposed to the change, as long as it's just a starting point from which we can later re-implement lifecycle subscriptions/services to effectively disconnect the entity.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

"In the inactive state, any data that arrives on managed topics will not be read and or processed. Data retention will be subject to the configured QoS policy for the topic."

for me, this design makes sense. that is the responsibility for QoS but LifecycleNode state. user can configure the behavior with QoS for LifecycleSubscription.

By the time you are dropping the message, you already wasted CPU cycles to go through all the ROS and network stack and potentially copying the message multiple times.

agree.

Specifically, the former is when subscriptions should be created and do discovery, and the latter is when you should start receiving data.

IMO, we need to add a new state for subscription. (the one is created and discovery, and the other is start taking the data from RMW queue(or wait_set is added))

I'd be OK with going forward with this implementation and a TODO that says implementing case 1 is future work.

i am good to go for now, with follow-up issue for this TODO.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

IMO, we need to add a new state for subscription. (the one is created and discovery, and the other is start taking the data from RMW queue(or wait_set is added))

I agree.
We are going to soon publish a proposal for updated lifecycle management and this is a topic we discussed while creating it.

Note that a similar concept applies also to non-lifecycle entities: a subscription may be visible but not added to any executor (or the executor may be not spinning), effectively making it "inactive"

@dadaroce
Copy link

dadaroce commented Feb 8, 2024

Any progress on this? looks like a really useful feature 😄

@fujitatomoya
Copy link
Collaborator

AFAIK, no progress. @carmiac are you going to work on this?

i think what we need to do is,

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants