@@ -55,12 +55,6 @@ class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
5555 explicit EmptyLifecycleNode (const std::string & node_name, const TimerType & timer_type)
5656 : rclcpp_lifecycle::LifecycleNode(node_name)
5757 {
58- rclcpp::PublisherOptionsWithAllocator<std::allocator<void >> options;
59- publisher_ =
60- std::make_shared<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>>(
61- get_node_base_interface ().get (), std::string (" topic" ), rclcpp::QoS (10 ), options);
62- add_managed_entity (publisher_);
63-
6458 // For coverage this is being added here
6559 switch (timer_type) {
6660 case TimerType::WALL_TIMER:
@@ -77,14 +71,6 @@ class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
7771 }
7872 }
7973 }
80-
81- std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher ()
82- {
83- return publisher_;
84- }
85-
86- private:
87- std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher_;
8874};
8975
9076class TestLifecyclePublisher : public ::testing::TestWithParam<TimerType>
@@ -93,95 +79,103 @@ class TestLifecyclePublisher : public ::testing::TestWithParam<TimerType>
9379 void SetUp ()
9480 {
9581 rclcpp::init (0 , nullptr );
96- node_ = std::make_shared<EmptyLifecycleNode>(" node" , GetParam ());
9782 }
9883
9984 void TearDown ()
10085 {
10186 rclcpp::shutdown ();
10287 }
103-
104- protected:
105- std::shared_ptr<EmptyLifecycleNode> node_;
10688};
10789
10890TEST_P (TestLifecyclePublisher, publish_managed_by_node) {
91+ auto node = std::make_shared<EmptyLifecycleNode>(" node" , GetParam ());
92+
93+ rclcpp::PublisherOptionsWithAllocator<std::allocator<void >> options;
94+ std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher =
95+ node->create_publisher <test_msgs::msg::Empty>(std::string (" topic" ), rclcpp::QoS (10 ), options);
96+
10997 // transition via LifecycleNode
11098 auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
11199 auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
112100 auto ret = reset_key;
113101
114- EXPECT_EQ (State::PRIMARY_STATE_UNCONFIGURED, node_ ->get_current_state ().id ());
115- node_ ->trigger_transition (
102+ EXPECT_EQ (State::PRIMARY_STATE_UNCONFIGURED, node ->get_current_state ().id ());
103+ node ->trigger_transition (
116104 rclcpp_lifecycle::Transition (Transition::TRANSITION_CONFIGURE), ret);
117105 ASSERT_EQ (success, ret);
118106 ret = reset_key;
119- node_ ->trigger_transition (
107+ node ->trigger_transition (
120108 rclcpp_lifecycle::Transition (Transition::TRANSITION_ACTIVATE), ret);
121109 ASSERT_EQ (success, ret);
122110 ret = reset_key;
123- EXPECT_TRUE (node_-> publisher () ->is_activated ());
111+ EXPECT_TRUE (publisher->is_activated ());
124112 {
125113 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
126- EXPECT_NO_THROW (node_-> publisher () ->publish (*msg_ptr));
114+ EXPECT_NO_THROW (publisher->publish (*msg_ptr));
127115 }
128116 {
129117 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
130- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (msg_ptr)));
118+ EXPECT_NO_THROW (publisher->publish (std::move (msg_ptr)));
131119 }
132120 {
133- auto loaned_msg = node_-> publisher () ->borrow_loaned_message ();
134- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (loaned_msg)));
121+ auto loaned_msg = publisher->borrow_loaned_message ();
122+ EXPECT_NO_THROW (publisher->publish (std::move (loaned_msg)));
135123 }
136- node_ ->trigger_transition (
124+ node ->trigger_transition (
137125 rclcpp_lifecycle::Transition (Transition::TRANSITION_DEACTIVATE), ret);
138126 ASSERT_EQ (success, ret);
139127 ret = reset_key;
140128 (void )ret; // Just to make clang happy
141- EXPECT_FALSE (node_-> publisher () ->is_activated ());
129+ EXPECT_FALSE (publisher->is_activated ());
142130 {
143131 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
144- EXPECT_NO_THROW (node_-> publisher () ->publish (*msg_ptr));
132+ EXPECT_NO_THROW (publisher->publish (*msg_ptr));
145133 }
146134 {
147135 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
148- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (msg_ptr)));
136+ EXPECT_NO_THROW (publisher->publish (std::move (msg_ptr)));
149137 }
150138 {
151- auto loaned_msg = node_-> publisher () ->borrow_loaned_message ();
152- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (loaned_msg)));
139+ auto loaned_msg = publisher->borrow_loaned_message ();
140+ EXPECT_NO_THROW (publisher->publish (std::move (loaned_msg)));
153141 }
154142}
155143
156144TEST_P (TestLifecyclePublisher, publish) {
145+ auto node = std::make_shared<EmptyLifecycleNode>(" node" , GetParam ());
146+
147+ rclcpp::PublisherOptionsWithAllocator<std::allocator<void >> options;
148+ std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<test_msgs::msg::Empty>> publisher =
149+ node->create_publisher <test_msgs::msg::Empty>(std::string (" topic" ), rclcpp::QoS (10 ), options);
150+
157151 // transition via LifecyclePublisher
158- node_-> publisher () ->on_deactivate ();
159- EXPECT_FALSE (node_-> publisher () ->is_activated ());
152+ publisher->on_deactivate ();
153+ EXPECT_FALSE (publisher->is_activated ());
160154 {
161155 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
162- EXPECT_NO_THROW (node_-> publisher () ->publish (*msg_ptr));
156+ EXPECT_NO_THROW (publisher->publish (*msg_ptr));
163157 }
164158 {
165159 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
166- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (msg_ptr)));
160+ EXPECT_NO_THROW (publisher->publish (std::move (msg_ptr)));
167161 }
168162 {
169- auto loaned_msg = node_-> publisher () ->borrow_loaned_message ();
170- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (loaned_msg)));
163+ auto loaned_msg = publisher->borrow_loaned_message ();
164+ EXPECT_NO_THROW (publisher->publish (std::move (loaned_msg)));
171165 }
172- node_-> publisher () ->on_activate ();
173- EXPECT_TRUE (node_-> publisher () ->is_activated ());
166+ publisher->on_activate ();
167+ EXPECT_TRUE (publisher->is_activated ());
174168 {
175169 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
176- EXPECT_NO_THROW (node_-> publisher () ->publish (*msg_ptr));
170+ EXPECT_NO_THROW (publisher->publish (*msg_ptr));
177171 }
178172 {
179173 auto msg_ptr = std::make_unique<test_msgs::msg::Empty>();
180- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (msg_ptr)));
174+ EXPECT_NO_THROW (publisher->publish (std::move (msg_ptr)));
181175 }
182176 {
183- auto loaned_msg = node_-> publisher () ->borrow_loaned_message ();
184- EXPECT_NO_THROW (node_-> publisher () ->publish (std::move (loaned_msg)));
177+ auto loaned_msg = publisher->borrow_loaned_message ();
178+ EXPECT_NO_THROW (publisher->publish (std::move (loaned_msg)));
185179 }
186180}
187181
0 commit comments