Skip to content

Commit 0522d7b

Browse files
committed
Add lifecycle subscriber and refactor create_subscription and subscription_factory as necessary.
Signed-of-by: Adam Milner <[email protected]> Signed-off-by: Adam Milner <[email protected]>
1 parent 22a954e commit 0522d7b

File tree

5 files changed

+97
-13
lines changed

5 files changed

+97
-13
lines changed

rclcpp/include/rclcpp/create_subscription.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -119,12 +119,13 @@ create_subscription(
119119
subscription_topic_stats->set_publisher_timer(timer);
120120
}
121121

122-
auto factory = rclcpp::create_subscription_factory<MessageT>(
122+
auto factory =
123+
rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT, SubscriptionT>(
123124
std::forward<CallbackT>(callback),
124125
options,
125126
msg_mem_strat,
126127
subscription_topic_stats
127-
);
128+
);
128129

129130
const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ?
130131
rclcpp::detail::declare_qos_parameters(

rclcpp/include/rclcpp/subscription_factory.hpp

+3-7
Original file line numberDiff line numberDiff line change
@@ -99,12 +99,9 @@ create_subscription_factory(
9999
rclcpp::node_interfaces::NodeBaseInterface * node_base,
100100
const std::string & topic_name,
101101
const rclcpp::QoS & qos
102-
) -> rclcpp::SubscriptionBase::SharedPtr
102+
) -> std::shared_ptr<SubscriptionT>
103103
{
104-
using rclcpp::Subscription;
105-
using rclcpp::SubscriptionBase;
106-
107-
auto sub = Subscription<MessageT, AllocatorT>::make_shared(
104+
auto sub = std::make_shared<SubscriptionT>(
108105
node_base,
109106
rclcpp::get_message_type_support_handle<MessageT>(),
110107
topic_name,
@@ -117,8 +114,7 @@ create_subscription_factory(
117114
// require this->shared_from_this() which cannot be called from
118115
// the constructor.
119116
sub->post_init_setup(node_base, qos, options);
120-
auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
121-
return sub_base_ptr;
117+
return sub;
122118
}
123119
};
124120

rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,7 @@
8888

8989
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
9090
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
91+
#include "rclcpp_lifecycle/lifecycle_subscriber.hpp"
9192
#include "rclcpp_lifecycle/state.hpp"
9293
#include "rclcpp_lifecycle/transition.hpp"
9394
#include "rclcpp_lifecycle/visibility_control.h"
@@ -240,7 +241,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
240241
typename MessageT,
241242
typename CallbackT,
242243
typename AllocatorT = std::allocator<void>,
243-
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
244+
typename SubscriptionT = rclcpp_lifecycle::LifecycleSubscription<MessageT, AllocatorT>,
244245
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType>
245246
std::shared_ptr<SubscriptionT>
246247
create_subscription(

rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343

4444
#include "rclcpp_lifecycle/lifecycle_node.hpp"
4545
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
46+
#include "rclcpp_lifecycle/lifecycle_subscriber.hpp"
4647
#include "rclcpp_lifecycle/visibility_control.h"
4748

4849
namespace rclcpp_lifecycle
@@ -65,12 +66,11 @@ LifecycleNode::create_publisher(
6566
return pub;
6667
}
6768

68-
// TODO(karsten1987): Create LifecycleSubscriber
6969
template<
7070
typename MessageT,
7171
typename CallbackT,
7272
typename AllocatorT,
73-
typename SubscriptionT,
73+
typename SubscriptionT = rclcpp_lifecycle::LifecycleSubscription<MessageT>,
7474
typename MessageMemoryStrategyT>
7575
std::shared_ptr<SubscriptionT>
7676
LifecycleNode::create_subscription(
@@ -80,13 +80,15 @@ LifecycleNode::create_subscription(
8080
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
8181
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
8282
{
83-
return rclcpp::create_subscription<MessageT>(
83+
auto sub = rclcpp::create_subscription<MessageT, CallbackT, AllocatorT, SubscriptionT>(
8484
*this,
8585
topic_name,
8686
qos,
8787
std::forward<CallbackT>(callback),
8888
options,
8989
msg_mem_strat);
90+
this->add_managed_entity(sub);
91+
return sub;
9092
}
9193

9294
template<typename DurationRepT, typename DurationT, typename CallbackT>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,84 @@
1+
// Copyright 2023 Elroy Air, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIPTION_HPP_
16+
#define RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIPTION_HPP_
17+
18+
// #include <functional>
19+
// #include <memory>
20+
21+
#include "rclcpp/subscription.hpp"
22+
23+
namespace rclcpp_lifecycle
24+
{
25+
26+
/// @brief Child class of rclcpp::Subscription that adds lifecycle functionality.
27+
/**
28+
* This class is a child class of rclcpp::Subscription that adds a lifecycle
29+
* check to the callback function. If the node is in an inactive state, the
30+
* callback will not be called.
31+
*/
32+
template<
33+
typename MessageT,
34+
typename AllocatorT = std::allocator<void>,
35+
typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type,
36+
typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type,
37+
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
38+
ROSMessageT,
39+
AllocatorT
40+
>>
41+
class LifecycleSubscription : public SimpleManagedEntity,
42+
public rclcpp::Subscription<MessageT, AllocatorT>
43+
{
44+
45+
private:
46+
using SubscriptionTopicStatisticsSharedPtr =
47+
std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<ROSMessageT>>;
48+
49+
public:
50+
LifecycleSubscription(
51+
rclcpp::node_interfaces::NodeBaseInterface * node_base,
52+
const rosidl_message_type_support_t & type_support_handle,
53+
const std::string & topic_name,
54+
const rclcpp::QoS & qos,
55+
rclcpp::AnySubscriptionCallback<MessageT, AllocatorT> callback,
56+
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
57+
typename MessageMemoryStrategyT::SharedPtr message_memory_strategy,
58+
SubscriptionTopicStatisticsSharedPtr subscription_topic_statistics = nullptr)
59+
: rclcpp::Subscription<MessageT>(
60+
node_base,
61+
type_support_handle,
62+
topic_name,
63+
qos,
64+
callback,
65+
options,
66+
message_memory_strategy,
67+
subscription_topic_statistics)
68+
{
69+
}
70+
71+
/// Check if we need to handle the message, and execute the callback if we do.
72+
virtual void handle_message(
73+
std::shared_ptr<void> & message, const rclcpp::MessageInfo & message_info) override
74+
{
75+
if (!this->is_activated()) {
76+
return;
77+
}
78+
rclcpp::Subscription<MessageT>::handle_message(message, message_info);
79+
}
80+
};
81+
82+
} // namespace rclcpp_lifecycle
83+
84+
#endif // RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIPTION_HPP_

0 commit comments

Comments
 (0)