Skip to content

Commit 009bc88

Browse files
Shut down the node
1 parent 46ecb88 commit 009bc88

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

test/pid_publisher_tests.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,6 @@ TEST(PidPublisherTest, PublishTestLifecycle)
7575
auto state_pub_lifecycle_ =
7676
std::dynamic_pointer_cast<rclcpp_lifecycle::LifecyclePublisher<control_msgs::msg::PidState>>(
7777
pid_ros.getPidStatePublisher());
78-
// state_pub_lifecycle_->on_activate();
7978

8079
pid_ros.initPid(1.0, 1.0, 1.0, 5.0, -5.0, false);
8180

@@ -97,8 +96,9 @@ TEST(PidPublisherTest, PublishTestLifecycle)
9796
rclcpp::spin_some(node->get_node_base_interface());
9897
std::this_thread::sleep_for(DELAY);
9998
}
100-
10199
ASSERT_TRUE(callback_called);
100+
101+
node->shutdown(); // won't be called in destructor
102102
}
103103

104104
int main(int argc, char ** argv)

0 commit comments

Comments
 (0)