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
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,12 +119,13 @@ create_subscription(
subscription_topic_stats->set_publisher_timer(timer);
}

auto factory = rclcpp::create_subscription_factory<MessageT>(
auto factory =
rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT, SubscriptionT>(
std::forward<CallbackT>(callback),
options,
msg_mem_strat,
subscription_topic_stats
);
);

const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ?
rclcpp::detail::declare_qos_parameters(
Expand Down
10 changes: 3 additions & 7 deletions rclcpp/include/rclcpp/subscription_factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,12 +99,9 @@ create_subscription_factory(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
const std::string & topic_name,
const rclcpp::QoS & qos
) -> rclcpp::SubscriptionBase::SharedPtr
) -> std::shared_ptr<SubscriptionT>
{
using rclcpp::Subscription;
using rclcpp::SubscriptionBase;

auto sub = Subscription<MessageT, AllocatorT>::make_shared(
auto sub = std::make_shared<SubscriptionT>(
node_base,
rclcpp::get_message_type_support_handle<MessageT>(),
topic_name,
Expand All @@ -117,8 +114,7 @@ create_subscription_factory(
// require this->shared_from_this() which cannot be called from
// the constructor.
sub->post_init_setup(node_base, qos, options);
auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
return sub_base_ptr;
return sub;
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@

#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "rclcpp_lifecycle/lifecycle_subscriber.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "rclcpp_lifecycle/transition.hpp"
#include "rclcpp_lifecycle/visibility_control.h"
Expand Down Expand Up @@ -240,7 +241,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename SubscriptionT = rclcpp_lifecycle::LifecycleSubscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType>
std::shared_ptr<SubscriptionT>
create_subscription(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@

#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "rclcpp_lifecycle/lifecycle_subscriber.hpp"
#include "rclcpp_lifecycle/visibility_control.h"

namespace rclcpp_lifecycle
Expand All @@ -65,12 +66,11 @@ LifecycleNode::create_publisher(
return pub;
}

// TODO(karsten1987): Create LifecycleSubscriber
template<
typename MessageT,
typename CallbackT,
typename AllocatorT,
typename SubscriptionT,
typename SubscriptionT = rclcpp_lifecycle::LifecycleSubscription<MessageT>,
typename MessageMemoryStrategyT>
std::shared_ptr<SubscriptionT>
LifecycleNode::create_subscription(
Expand All @@ -80,13 +80,15 @@ LifecycleNode::create_subscription(
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
{
return rclcpp::create_subscription<MessageT>(
auto sub = rclcpp::create_subscription<MessageT, CallbackT, AllocatorT, SubscriptionT>(
*this,
topic_name,
qos,
std::forward<CallbackT>(callback),
options,
msg_mem_strat);
this->add_managed_entity(sub);
return sub;
}

template<typename DurationRepT, typename DurationT, typename CallbackT>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
// Copyright 2023 Elroy Air, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIBER_HPP_
#define RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIBER_HPP_

#include <memory>
#include <string>

#include "rclcpp/subscription.hpp"

namespace rclcpp_lifecycle
{

/// @brief Child class of rclcpp::Subscription that adds lifecycle functionality.
/**
* This class is a child class of rclcpp::Subscription that adds a lifecycle
* check to the callback function. If the node is in an inactive state, the
* callback will not be called.
*/
template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type,
typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type,
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
ROSMessageT,
AllocatorT
>>
class LifecycleSubscription : public SimpleManagedEntity,
public rclcpp::Subscription<MessageT, AllocatorT>
{
private:
using SubscriptionTopicStatisticsSharedPtr =
std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<ROSMessageT>>;

public:
LifecycleSubscription(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
const rosidl_message_type_support_t & type_support_handle,
const std::string & topic_name,
const rclcpp::QoS & qos,
rclcpp::AnySubscriptionCallback<MessageT, AllocatorT> callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
typename MessageMemoryStrategyT::SharedPtr message_memory_strategy,
SubscriptionTopicStatisticsSharedPtr subscription_topic_statistics = nullptr)
: rclcpp::Subscription<MessageT>(
node_base,
type_support_handle,
topic_name,
qos,
callback,
options,
message_memory_strategy,
subscription_topic_statistics)
{
}

/// 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);
}
Comment on lines +70 to +78
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"

};

} // namespace rclcpp_lifecycle

#endif // RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIBER_HPP_