Skip to content

Commit 113024c

Browse files
committed
Add LifecycleSubscription
Signed-off-by: Aarav Gupta <[email protected]>
1 parent a0a2a06 commit 113024c

File tree

7 files changed

+275
-16
lines changed

7 files changed

+275
-16
lines changed

rclcpp/include/rclcpp/create_subscription.hpp

+7-6
Original file line numberDiff line numberDiff line change
@@ -118,12 +118,13 @@ create_subscription(
118118
subscription_topic_stats->set_publisher_timer(timer);
119119
}
120120

121-
auto factory = rclcpp::create_subscription_factory<MessageT>(
122-
std::forward<CallbackT>(callback),
123-
options,
124-
msg_mem_strat,
125-
subscription_topic_stats
126-
);
121+
auto factory =
122+
rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT, SubscriptionT>(
123+
std::forward<CallbackT>(callback),
124+
options,
125+
msg_mem_strat,
126+
subscription_topic_stats
127+
);
127128

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

rclcpp/include/rclcpp/subscription_factory.hpp

+3-7
Original file line numberDiff line numberDiff line change
@@ -98,12 +98,9 @@ create_subscription_factory(
9898
rclcpp::node_interfaces::NodeBaseInterface * node_base,
9999
const std::string & topic_name,
100100
const rclcpp::QoS & qos
101-
) -> rclcpp::SubscriptionBase::SharedPtr
101+
) -> std::shared_ptr<SubscriptionT>
102102
{
103-
using rclcpp::Subscription;
104-
using rclcpp::SubscriptionBase;
105-
106-
auto sub = Subscription<MessageT, AllocatorT>::make_shared(
103+
auto sub = std::make_shared<SubscriptionT>(
107104
node_base,
108105
rclcpp::get_message_type_support_handle<MessageT>(),
109106
topic_name,
@@ -116,8 +113,7 @@ create_subscription_factory(
116113
// require this->shared_from_this() which cannot be called from
117114
// the constructor.
118115
sub->post_init_setup(node_base, qos, options);
119-
auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
120-
return sub_base_ptr;
116+
return sub;
121117
}
122118
};
123119

rclcpp_lifecycle/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,10 @@ if(BUILD_TESTING)
110110
if(TARGET test_lifecycle_publisher)
111111
target_link_libraries(test_lifecycle_publisher ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp ${test_msgs_TARGETS})
112112
endif()
113+
ament_add_gtest(test_lifecycle_subscription test/test_lifecycle_subscription.cpp)
114+
if(TARGET test_lifecycle_subscription)
115+
target_link_libraries(test_lifecycle_subscription ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp ${test_msgs_TARGETS})
116+
endif()
113117
ament_add_gtest(test_lifecycle_service_client test/test_lifecycle_service_client.cpp TIMEOUT 120)
114118
ament_add_test_label(test_lifecycle_service_client mimick)
115119
if(TARGET test_lifecycle_service_client)

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_subscription.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

+4-2
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include "rclcpp/subscription_options.hpp"
4040
#include "rclcpp/type_support_decl.hpp"
4141

42+
#include "rclcpp_lifecycle/lifecycle_subscription.hpp"
4243
#include "rmw/types.h"
4344

4445
#include "rclcpp_lifecycle/lifecycle_node.hpp"
@@ -65,7 +66,6 @@ LifecycleNode::create_publisher(
6566
return pub;
6667
}
6768

68-
// TODO(karsten1987): Create LifecycleSubscriber
6969
template<
7070
typename MessageT,
7171
typename CallbackT,
@@ -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,90 @@
1+
// Copyright 2024 Open Source Robotics Foundation, 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 <memory>
19+
#include <string>
20+
21+
#include "rclcpp/node_interfaces/node_base_interface.hpp"
22+
#include "rclcpp/subscription.hpp"
23+
#include "rclcpp/subscription_options.hpp"
24+
#include "rclcpp/qos.hpp"
25+
26+
#include "rclcpp_lifecycle/managed_entity.hpp"
27+
28+
29+
namespace rclcpp_lifecycle
30+
{
31+
32+
/// @brief Child class of rclcpp::Subscription that adds lifecycle functionality.
33+
/**
34+
* This class is a child class of rclcpp::Subscription that adds a lifecycle
35+
* check to the callback function. If the node is in an inactive state, the
36+
* callback will not be called.
37+
*/
38+
template<
39+
typename MessageT,
40+
typename AllocatorT = std::allocator<void>,
41+
typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type,
42+
typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type,
43+
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
44+
ROSMessageT,
45+
AllocatorT
46+
>>
47+
class LifecycleSubscription : public SimpleManagedEntity,
48+
public rclcpp::Subscription<MessageT, AllocatorT>
49+
{
50+
private:
51+
using SubscriptionTopicStatisticsSharedPtr =
52+
std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>;
53+
54+
public:
55+
LifecycleSubscription(
56+
rclcpp::node_interfaces::NodeBaseInterface * node_base,
57+
const rosidl_message_type_support_t & type_support_handle,
58+
const std::string & topic_name,
59+
const rclcpp::QoS & qos,
60+
rclcpp::AnySubscriptionCallback<MessageT, AllocatorT> callback,
61+
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
62+
typename MessageMemoryStrategyT::SharedPtr message_memory_strategy,
63+
SubscriptionTopicStatisticsSharedPtr subscription_topic_statistics = nullptr)
64+
: rclcpp::Subscription<MessageT>(
65+
node_base,
66+
type_support_handle,
67+
topic_name,
68+
qos,
69+
callback,
70+
options,
71+
message_memory_strategy,
72+
subscription_topic_statistics)
73+
{
74+
}
75+
76+
/// TODO: Hold onto the data that arrives before activation, and deliver that on activation.
77+
/// Check if we need to handle the message, and execute the callback if we do.
78+
void handle_message(
79+
std::shared_ptr<void> & message, const rclcpp::MessageInfo & message_info) override
80+
{
81+
if (!this->is_activated()) {
82+
return;
83+
}
84+
rclcpp::Subscription<MessageT, AllocatorT>::handle_message(message, message_info);
85+
}
86+
};
87+
88+
} // namespace rclcpp_lifecycle
89+
90+
#endif // RCLCPP_LIFECYCLE__LIFECYCLE_SUBSCRIPTION_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,165 @@
1+
// Copyright 2024 Open Source Robotics Foundation, 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+
#include <gtest/gtest.h>
16+
#include <memory>
17+
#include <string>
18+
19+
#include "lifecycle_msgs/msg/state.hpp"
20+
#include "lifecycle_msgs/msg/transition.hpp"
21+
22+
#include "test_msgs/msg/empty.hpp"
23+
24+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
25+
#include "rclcpp_lifecycle/lifecycle_subscription.hpp"
26+
27+
using lifecycle_msgs::msg::State;
28+
using lifecycle_msgs::msg::Transition;
29+
30+
class TestDefaultStateMachine : public ::testing::Test
31+
{
32+
protected:
33+
static void SetUpTestCase()
34+
{
35+
rclcpp::init(0, nullptr);
36+
}
37+
static void TearDownTestCase()
38+
{
39+
rclcpp::shutdown();
40+
}
41+
};
42+
43+
/// We want to test everything for both the wall and generic timer.
44+
enum class TimerType
45+
{
46+
WALL_TIMER,
47+
GENERIC_TIMER,
48+
};
49+
50+
class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
51+
{
52+
public:
53+
explicit EmptyLifecycleNode(const std::string & node_name, const TimerType & timer_type)
54+
: rclcpp_lifecycle::LifecycleNode(node_name)
55+
{
56+
// For coverage this is being added here
57+
switch (timer_type) {
58+
case TimerType::WALL_TIMER:
59+
{
60+
auto timer = create_wall_timer(std::chrono::seconds(1), []() {});
61+
add_timer_handle(timer);
62+
break;
63+
}
64+
case TimerType::GENERIC_TIMER:
65+
{
66+
auto timer = create_timer(std::chrono::seconds(1), []() {});
67+
add_timer_handle(timer);
68+
break;
69+
}
70+
}
71+
}
72+
73+
void empty_callback(const test_msgs::msg::Empty msg) {}
74+
};
75+
76+
class TestLifecycleSubscription : public ::testing::TestWithParam<TimerType>
77+
{
78+
public:
79+
void SetUp()
80+
{
81+
rclcpp::init(0, nullptr);
82+
}
83+
84+
void TearDown()
85+
{
86+
rclcpp::shutdown();
87+
}
88+
};
89+
90+
TEST_P(TestLifecycleSubscription, subscribe_managed_by_node) {
91+
auto node = std::make_shared<EmptyLifecycleNode>("node", GetParam());
92+
93+
std::shared_ptr<rclcpp_lifecycle::LifecycleSubscription<test_msgs::msg::Empty>> subscription =
94+
node->create_subscription<test_msgs::msg::Empty>(std::string("topic"), rclcpp::QoS(10),
95+
bind(&EmptyLifecycleNode::empty_callback, node, std::placeholders::_1));
96+
97+
// transition via LifecycleNode
98+
auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
99+
auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
100+
auto ret = reset_key;
101+
102+
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, node->get_current_state().id());
103+
node->trigger_transition(
104+
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE), ret);
105+
ASSERT_EQ(success, ret);
106+
ret = reset_key;
107+
node->trigger_transition(
108+
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE), ret);
109+
ASSERT_EQ(success, ret);
110+
ret = reset_key;
111+
EXPECT_TRUE(subscription->is_activated());
112+
{
113+
std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());
114+
EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));
115+
}
116+
node->trigger_transition(
117+
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE), ret);
118+
ASSERT_EQ(success, ret);
119+
ret = reset_key;
120+
(void)ret; // Just to make clang happy
121+
EXPECT_FALSE(subscription->is_activated());
122+
{
123+
std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());
124+
EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));
125+
}
126+
}
127+
128+
TEST_P(TestLifecycleSubscription, subscribe) {
129+
auto node = std::make_shared<EmptyLifecycleNode>("node", GetParam());
130+
131+
std::shared_ptr<rclcpp_lifecycle::LifecycleSubscription<test_msgs::msg::Empty>> subscription =
132+
node->create_subscription<test_msgs::msg::Empty>(std::string("topic"), rclcpp::QoS(10),
133+
bind(&EmptyLifecycleNode::empty_callback, node, std::placeholders::_1));
134+
135+
// transition via LifecycleSubscription
136+
subscription->on_deactivate();
137+
EXPECT_FALSE(subscription->is_activated());
138+
{
139+
std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());
140+
EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));
141+
}
142+
143+
subscription->on_activate();
144+
EXPECT_TRUE(subscription->is_activated());
145+
{
146+
std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());
147+
EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));
148+
}
149+
}
150+
151+
INSTANTIATE_TEST_SUITE_P(
152+
PerTimerType, TestLifecycleSubscription,
153+
::testing::Values(TimerType::WALL_TIMER, TimerType::GENERIC_TIMER),
154+
[](const ::testing::TestParamInfo<TimerType> & info) -> std::string {
155+
switch (info.param) {
156+
case TimerType::WALL_TIMER:
157+
return std::string("wall_timer");
158+
case TimerType::GENERIC_TIMER:
159+
return std::string("generic_timer");
160+
default:
161+
break;
162+
}
163+
return std::string("unknown");
164+
}
165+
);

0 commit comments

Comments
 (0)