Skip to content

Commit

Permalink
Improve the node_name test. (#538)
Browse files Browse the repository at this point in the history
We do a few things here:

1.  Minor style updates, just to make the code easier to read.
2.  Increase the timeout for finding the node from 10 seconds
    to 15 seconds.
3.  Change the call to the executor from spin_once to spin_some.
    This means that we'll give the executor more opportunity to
    do work, which may increase the chances of success.

Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette committed Mar 9, 2024
1 parent 3f6fd66 commit 243e491
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 12 deletions.
18 changes: 11 additions & 7 deletions test_rclcpp/test/node_name_list.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <cstdio>
#include <iostream>
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"

Expand Down Expand Up @@ -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<std::string> 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;
}
Expand All @@ -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);
Expand Down
10 changes: 5 additions & 5 deletions test_rclcpp/test/node_with_name.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <cstdio>
#include <iostream>
#include <string>

#include "rclcpp/rclcpp.hpp"
Expand All @@ -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;
}

0 comments on commit 243e491

Please sign in to comment.