@@ -258,6 +258,7 @@ class ActionTest : public ::testing::Test
258258
259259TEST_F (ActionTest, test_simple_action)
260260{
261+ std::this_thread::sleep_for (std::chrono::milliseconds (1000 ));
261262 node_->activate_server ();
262263
263264 // The goal for this invocation
@@ -272,6 +273,7 @@ TEST_F(ActionTest, test_simple_action)
272273 future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
273274
274275 auto goal_handle = future_goal_handle.get ();
276+ EXPECT_NE (goal_handle, nullptr );
275277
276278 // Wait for the result
277279 auto future_result = node_->action_client_ ->async_get_result (goal_handle);
@@ -320,6 +322,7 @@ TEST_F(ActionTest, test_simple_action_with_feedback)
320322 future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
321323
322324 auto goal_handle = future_goal_handle.get ();
325+ EXPECT_NE (goal_handle, nullptr );
323326
324327 // Wait for the result
325328 auto future_result = node_->action_client_ ->async_get_result (goal_handle);
@@ -364,6 +367,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling)
364367 node_->deactivate_server ();
365368
366369 auto goal_handle = future_goal_handle.get ();
370+ EXPECT_NE (goal_handle, nullptr );
367371
368372 // Wait for the result
369373 auto future_result = node_->action_client_ ->async_get_result (goal_handle);
@@ -430,6 +434,7 @@ TEST_F(ActionTest, test_simple_action_preemption)
430434 future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
431435
432436 auto goal_handle = future_goal_handle.get ();
437+ EXPECT_NE (goal_handle, nullptr );
433438
434439 // Wait for the result
435440 auto future_result = node_->action_client_ ->async_get_result (goal_handle);
@@ -478,6 +483,7 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded)
478483
479484 // Get the results
480485 auto goal_handle = future_goal_handle.get ();
486+ EXPECT_NE (goal_handle, nullptr );
481487
482488 // Wait for the result of initial goal
483489 auto future_result = node_->action_client_ ->async_get_result (goal_handle);
0 commit comments