File tree Expand file tree Collapse file tree 2 files changed +6
-6
lines changed
rclcpp/minimal_subscriber Expand file tree Collapse file tree 2 files changed +6
-6
lines changed Original file line number Diff line number Diff line change @@ -23,14 +23,14 @@ ament_target_dependencies(subscriber_member_function rclcpp std_msgs)
2323add_executable (subscriber_not_composable not_composable.cpp)
2424ament_target_dependencies(subscriber_not_composable rclcpp std_msgs)
2525
26- add_executable (waitset waitset .cpp)
27- ament_target_dependencies(waitset rclcpp std_msgs)
26+ add_executable (subscriber_waitset subscriber_waitset .cpp)
27+ ament_target_dependencies(subscriber_waitset rclcpp std_msgs)
2828
2929install (TARGETS
3030 subscriber_lambda
3131 subscriber_member_function
3232 subscriber_not_composable
33- waitset
33+ subscriber_waitset
3434 DESTINATION lib/${PROJECT_NAME} )
3535
3636ament_package()
Original file line number Diff line number Diff line change @@ -42,7 +42,7 @@ class MinimalSubscriber : public rclcpp::Node
4242 rclcpp::WaitSet wait_set;
4343 wait_set.add_subscription (subscription_);
4444 while (rclcpp::ok ()) {
45- const auto wait_result = wait_set.wait ();
45+ const auto wait_result = wait_set.wait (std::chrono::seconds ( 1 ) );
4646 if (wait_result.kind () == rclcpp::WaitResultKind::Ready) {
4747 if (wait_result.get_wait_set ().get_rcl_wait_set ().subscriptions [0U ]) {
4848 std_msgs::msg::String msg;
@@ -65,12 +65,13 @@ int main(int argc, char * argv[])
6565 rclcpp::init (argc, argv);
6666 auto node = std::make_shared<MinimalSubscriber>();
6767
68+
6869 // Option 1: loop in main
6970 auto sub = node->get_subscription ();
7071 rclcpp::WaitSet wait_set;
7172 wait_set.add_subscription (sub);
7273 while (rclcpp::ok ()) {
73- const auto wait_result = wait_set.wait ();
74+ const auto wait_result = wait_set.wait (std::chrono::seconds ( 1 ) );
7475 if (wait_result.kind () == rclcpp::WaitResultKind::Ready) {
7576 if (wait_result.get_wait_set ().get_rcl_wait_set ().subscriptions [0U ]) {
7677 std_msgs::msg::String msg;
@@ -86,7 +87,6 @@ int main(int argc, char * argv[])
8687 // Option 2: run node
8788 // node->run();
8889
89- // rclcpp::spin();
9090 rclcpp::shutdown ();
9191 return 0 ;
9292}
You can’t perform that action at this time.
0 commit comments