Skip to content

Commit

Permalink
nav2_system_tests: behaviour_tree error_code, error_msg checks (#4341)
Browse files Browse the repository at this point in the history
  • Loading branch information
aosmw committed Sep 13, 2024
1 parent 10f2852 commit 62e2ee8
Showing 1 changed file with 16 additions and 16 deletions.
32 changes: 16 additions & 16 deletions nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -343,12 +343,12 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateSubtreeRecoveries)

// Goal count should be 2 since only two goals were sent to ComputePathToPose and FollowPath
EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 2);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 207);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "Timeout");

EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 2);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 106);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "No valid control");

// Navigate subtree recovery services are called once each
EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 1);
Expand Down Expand Up @@ -406,13 +406,13 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoverySimple)

// FollowPath is called 4 times
EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 4);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 106);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "No valid control");

// ComputePathToPose is called 3 times
EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 3);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 207);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "Timeout");

// Local costmap is cleared 3 times
EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 3);
Expand Down Expand Up @@ -504,13 +504,13 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoveryComplex)

// ComputePathToPose is called 12 times
EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 7);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 207);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "Timeout");

// FollowPath is called 4 times
EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 14);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 106);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "No valid control");

// Local costmap is cleared 5 times
EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 9);
Expand Down Expand Up @@ -587,13 +587,13 @@ TEST_F(BehaviorTreeTestFixture, TestRecoverySubtreeGoalUpdated)

// ComputePathToPose is called 4 times
EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 3);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_code, 207);
EXPECT_EQ(server_handler->compute_path_to_pose_server->fillResult()->error_msg, "Timeout");

// FollowPath is called 3 times
EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 5);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 0);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "");
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_code, 106);
EXPECT_EQ(server_handler->follow_path_server->fillResult()->error_msg, "No valid control");

// Local costmap is cleared 2 times
EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 3);
Expand Down

0 comments on commit 62e2ee8

Please sign in to comment.