Skip to content

Commit f95ac7c

Browse files
rclcpp::shutdown should not be called before LifecycleNode dtor. (backport ros2#2527) (ros2#2538)
* rclcpp::shutdown should not be called before LifecycleNode dtor. (ros2#2527) Signed-off-by: Tomoya Fujita <[email protected]> (cherry picked from commit 22df1d5) # Conflicts: # rclcpp_lifecycle/test/test_lifecycle_publisher.cpp * resolve conflicts. Signed-off-by: Tomoya Fujita <[email protected]> --------- Signed-off-by: Tomoya Fujita <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]>
1 parent 844ab6b commit f95ac7c

File tree

1 file changed

+30
-36
lines changed

1 file changed

+30
-36
lines changed

rclcpp_lifecycle/test/test_lifecycle_publisher.cpp

Lines changed: 30 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -48,24 +48,10 @@ class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
4848
explicit EmptyLifecycleNode(const std::string & node_name)
4949
: rclcpp_lifecycle::LifecycleNode(node_name)
5050
{
51-
rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
52-
publisher_ =
53-
std::make_shared<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>>(
54-
get_node_base_interface().get(), std::string("topic"), rclcpp::QoS(10), options);
55-
add_managed_entity(publisher_);
56-
5751
// For coverage this is being added here
5852
auto timer = create_wall_timer(std::chrono::seconds(1), []() {});
5953
add_timer_handle(timer);
6054
}
61-
62-
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher()
63-
{
64-
return publisher_;
65-
}
66-
67-
private:
68-
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher_;
6955
};
7056

7157
class TestLifecyclePublisher : public ::testing::Test
@@ -74,77 +60,85 @@ class TestLifecyclePublisher : public ::testing::Test
7460
void SetUp()
7561
{
7662
rclcpp::init(0, nullptr);
77-
node_ = std::make_shared<EmptyLifecycleNode>("node");
7863
}
7964

8065
void TearDown()
8166
{
8267
rclcpp::shutdown();
8368
}
84-
85-
protected:
86-
std::shared_ptr<EmptyLifecycleNode> node_;
8769
};
8870

8971
TEST_F(TestLifecyclePublisher, publish_managed_by_node) {
72+
auto node = std::make_shared<EmptyLifecycleNode>("node");
73+
74+
rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
75+
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher =
76+
node->create_publisher<test_msgs::msg::Empty>(std::string("topic"), rclcpp::QoS(10), options);
77+
9078
// transition via LifecycleNode
9179
auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
9280
auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
9381
auto ret = reset_key;
9482

95-
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, node_->get_current_state().id());
96-
node_->trigger_transition(
83+
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, node->get_current_state().id());
84+
node->trigger_transition(
9785
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE), ret);
9886
ASSERT_EQ(success, ret);
9987
ret = reset_key;
100-
node_->trigger_transition(
88+
node->trigger_transition(
10189
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE), ret);
10290
ASSERT_EQ(success, ret);
10391
ret = reset_key;
104-
EXPECT_TRUE(node_->publisher()->is_activated());
92+
EXPECT_TRUE(publisher->is_activated());
10593
{
10694
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
107-
EXPECT_NO_THROW(node_->publisher()->publish(*msg_ptr));
95+
EXPECT_NO_THROW(publisher->publish(*msg_ptr));
10896
}
10997
{
11098
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
111-
EXPECT_NO_THROW(node_->publisher()->publish(std::move(msg_ptr)));
99+
EXPECT_NO_THROW(publisher->publish(std::move(msg_ptr)));
112100
}
113-
node_->trigger_transition(
101+
node->trigger_transition(
114102
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE), ret);
115103
ASSERT_EQ(success, ret);
116104
ret = reset_key;
117-
EXPECT_FALSE(node_->publisher()->is_activated());
105+
EXPECT_FALSE(publisher->is_activated());
118106
{
119107
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
120-
EXPECT_NO_THROW(node_->publisher()->publish(*msg_ptr));
108+
EXPECT_NO_THROW(publisher->publish(*msg_ptr));
121109
}
122110
{
123111
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
124-
EXPECT_NO_THROW(node_->publisher()->publish(std::move(msg_ptr)));
112+
EXPECT_NO_THROW(publisher->publish(std::move(msg_ptr)));
125113
}
126114
}
127115

128116
TEST_F(TestLifecyclePublisher, publish) {
117+
auto node = std::make_shared<EmptyLifecycleNode>("node");
118+
119+
rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
120+
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher =
121+
node->create_publisher<test_msgs::msg::Empty>(std::string("topic"), rclcpp::QoS(10), options);
122+
129123
// transition via LifecyclePublisher
130-
node_->publisher()->on_deactivate();
131-
EXPECT_FALSE(node_->publisher()->is_activated());
124+
publisher->on_deactivate();
125+
EXPECT_FALSE(publisher->is_activated());
132126
{
133127
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
134-
EXPECT_NO_THROW(node_->publisher()->publish(*msg_ptr));
128+
EXPECT_NO_THROW(publisher->publish(*msg_ptr));
135129
}
136130
{
137131
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
138-
EXPECT_NO_THROW(node_->publisher()->publish(std::move(msg_ptr)));
132+
EXPECT_NO_THROW(publisher->publish(std::move(msg_ptr)));
139133
}
140-
node_->publisher()->on_activate();
141-
EXPECT_TRUE(node_->publisher()->is_activated());
134+
publisher->on_activate();
135+
EXPECT_TRUE(publisher->is_activated());
142136
{
143137
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
144-
EXPECT_NO_THROW(node_->publisher()->publish(*msg_ptr));
138+
EXPECT_NO_THROW(publisher->publish(*msg_ptr));
145139
}
146140
{
147141
auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
148-
EXPECT_NO_THROW(node_->publisher()->publish(std::move(msg_ptr)));
142+
EXPECT_NO_THROW(publisher->publish(std::move(msg_ptr)));
149143
}
150144
}

0 commit comments

Comments
 (0)