Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 13 additions & 2 deletions nav2_system_tests/src/behaviors/spin/spin_behavior_tester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,9 @@ void SpinBehaviorTester::deactivate()

bool SpinBehaviorTester::defaultSpinBehaviorTest(
const float target_yaw,
const double tolerance)
const double tolerance,
const bool nonblocking_action,
const bool cancel_action)
{
if (!is_active_) {
RCLCPP_ERROR(node_->get_logger(), "Not activated");
Expand Down Expand Up @@ -181,6 +183,16 @@ bool SpinBehaviorTester::defaultSpinBehaviorTest(
return false;
}

if (!nonblocking_action) {
return true;
}
if (cancel_action) {
sleep(2);
// cancel the goal
auto cancel_response = client_ptr_->async_cancel_goal(goal_handle_future.get());
rclcpp::spin_until_future_complete(node_, cancel_response);
}

// Wait for the server to be done with the goal
auto result_future = client_ptr_->async_get_result(goal_handle);

Expand Down Expand Up @@ -347,5 +359,4 @@ void SpinBehaviorTester::amclPoseCallback(
{
initial_pose_received_ = true;
}

} // namespace nav2_system_tests
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,9 @@ class SpinBehaviorTester
// Runs a single test with given target yaw
bool defaultSpinBehaviorTest(
float target_yaw,
double tolerance = 0.1);
double tolerance = 0.1,
bool nonblocking_action = true,
bool cancel_action = false);

void activate();

Expand Down
34 changes: 34 additions & 0 deletions nav2_system_tests/src/behaviors/spin/test_spin_behavior_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,40 @@ TEST_P(SpinBehaviorTestFixture, testSpinRecovery)
}
}

TEST_F(SpinBehaviorTestFixture, testSpinPreemption)
{
// Goal
float target_yaw = 3.0 * M_PIf32;
float tolerance = 0.1;
bool nonblocking_action = false;
bool success = false;

// Send the first goal
success = spin_recovery_tester->defaultSpinBehaviorTest(
target_yaw, tolerance,
nonblocking_action);
EXPECT_EQ(true, success);
// Preempt goal
sleep(2);
success = false;
float prempt_target_yaw = 4.0 * M_PIf32;
float preempt_tolerance = 0.1;
success = spin_recovery_tester->defaultSpinBehaviorTest(prempt_target_yaw, preempt_tolerance);
EXPECT_EQ(false, success);
}

TEST_F(SpinBehaviorTestFixture, testSpinCancel)
{
// Goal
float target_yaw = 4.0 * M_PIf32;
float tolerance = 0.1;
bool nonblocking_action = true, cancel_action = true, success = false;
success = spin_recovery_tester->defaultSpinBehaviorTest(
target_yaw, tolerance,
nonblocking_action, cancel_action);
EXPECT_EQ(false, success);
}

INSTANTIATE_TEST_SUITE_P(
SpinRecoveryTests,
SpinBehaviorTestFixture,
Expand Down