Skip to content

Commit

Permalink
Add lifecycle subscriber and refactor create_subscription and subscri…
Browse files Browse the repository at this point in the history
…ption_factory as necessary.

Signed-of-by: Adam Milner <[email protected]>
Signed-off-by: Adam Milner <[email protected]>
  • Loading branch information
carmiac committed Aug 1, 2023
1 parent 22a954e commit 0522d7b
Show file tree
Hide file tree
Showing 5 changed files with 97 additions and 13 deletions.
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
3 changes: 2 additions & 1 deletion rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
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
84 changes: 84 additions & 0 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_subscriber.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
// 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_SUBSCRIPTION_HPP_
#define RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIPTION_HPP_

// #include <functional>
// #include <memory>

#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.
virtual 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);
}
};

} // namespace rclcpp_lifecycle

#endif // RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIPTION_HPP_

0 comments on commit 0522d7b

Please sign in to comment.