diff --git a/test_rclcpp/test/node_name_list.cpp b/test_rclcpp/test/node_name_list.cpp index cd7d3217..62784c46 100644 --- a/test_rclcpp/test/node_name_list.cpp +++ b/test_rclcpp/test/node_name_list.cpp @@ -12,7 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include +#include +#include #include +#include #include "rclcpp/rclcpp.hpp" @@ -40,19 +44,19 @@ int main(int argc, char ** argv) int rc = 1; const std::chrono::steady_clock::time_point max_runtime = - std::chrono::steady_clock::now() + 10s; + std::chrono::steady_clock::now() + 15s; while (rc && rclcpp::ok()) { - auto names = node->get_node_graph_interface()->get_node_names(); - for (auto it : names) { - printf("- %s\n", it.c_str()); + std::vector names = node->get_node_names(); + for (const std::string & name : names) { + printf("- %s\n", name.c_str()); - if (it.empty()) { + if (name.empty()) { printf(" found an empty named node, which is unexpected\n"); rc = 2; break; } - if (argc >= 2 && it.compare(name_to_find) == 0) { + if (argc >= 2 && name.compare(name_to_find) == 0) { printf(" found expected node name\n"); rc = 0; } @@ -61,7 +65,7 @@ int main(int argc, char ** argv) if (std::chrono::steady_clock::now() >= max_runtime) { break; } - exec.spin_once(250ms); + exec.spin_some(250ms); } exec.remove_node(node); diff --git a/test_rclcpp/test/node_with_name.cpp b/test_rclcpp/test/node_with_name.cpp index df430d57..3ff5932e 100644 --- a/test_rclcpp/test/node_with_name.cpp +++ b/test_rclcpp/test/node_with_name.cpp @@ -12,6 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include +#include #include #include "rclcpp/rclcpp.hpp" @@ -30,15 +32,13 @@ int main(int argc, char ** argv) rclcpp::Node::SharedPtr node; try { - node = rclcpp::Node::make_shared(node_name); - } catch (rclcpp::exceptions::RCLError & e) { + rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name); + rclcpp::spin(node); + } catch (const rclcpp::exceptions::RCLError & e) { // test may pass and send SIGINT before node finishes initializing ros2/build_cop#153 printf("Ignoring RCLError: %s\n", e.what()); } - if (node) { - rclcpp::spin(node); - } rclcpp::shutdown(); return 0; }