Skip to content

Commit

Permalink
Use spin instead of spin_some
Browse files Browse the repository at this point in the history
  • Loading branch information
bjsowa committed Jul 16, 2024
1 parent 4aefec2 commit 0597364
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 14 deletions.
8 changes: 1 addition & 7 deletions src/scan_to_cloud_filter_chain_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,13 +47,7 @@ main(int argc, char ** argv)
rclcpp::init(argc, argv);
auto filter_chain = std::make_shared<ScanToCloudFilterChain>();

rclcpp::WallRate loop_rate(200);
while (rclcpp::ok()) {

rclcpp::spin_some(filter_chain->get_node_base_interface());
loop_rate.sleep();

}
rclcpp::spin(filter_chain);

return 0;
}
8 changes: 1 addition & 7 deletions src/scan_to_scan_filter_chain_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,13 +47,7 @@ main(int argc, char ** argv)
rclcpp::init(argc, argv);
auto filter_chain = std::make_shared<ScanToScanFilterChain>();

rclcpp::WallRate loop_rate(200);
while (rclcpp::ok()) {

rclcpp::spin_some(filter_chain->get_node_base_interface());
loop_rate.sleep();

}
rclcpp::spin(filter_chain);

return 0;
}

0 comments on commit 0597364

Please sign in to comment.