@@ -852,6 +852,83 @@ TEST_F(TestClientAgainstServer, async_cancel_some_goals_with_callback)
852852 EXPECT_EQ (rclcpp_action::GoalStatus::STATUS_CANCELED, goal_handle0->get_status ());
853853}
854854
855+
856+ TEST_F (TestClientAgainstServer, deadlock_in_callbacks)
857+ {
858+ std::atomic<bool > feedback_callback_called = false ;
859+ std::atomic<bool > response_callback_called = false ;
860+ std::atomic<bool > result_callback_called = false ;
861+ std::atomic<bool > test_done = false ;
862+
863+ std::thread tr = std::thread (
864+ [&]() {
865+ auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
866+ ASSERT_TRUE (action_client->wait_for_action_server (WAIT_FOR_SERVER_TIMEOUT));
867+
868+ ActionGoal goal;
869+
870+ using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>;
871+ rclcpp_action::Client<ActionType>::SendGoalOptions ops;
872+ ops.feedback_callback =
873+ [&feedback_callback_called](const GoalHandle::SharedPtr handle,
874+ ActionType::Feedback::ConstSharedPtr) {
875+ // call functions on the handle that acquire the lock
876+ handle->get_status ();
877+ handle->is_feedback_aware ();
878+ handle->is_result_aware ();
879+
880+ feedback_callback_called = true ;
881+ };
882+ ops.goal_response_callback = [&response_callback_called](
883+ const GoalHandle::SharedPtr & handle) {
884+ // call functions on the handle that acquire the lock
885+ handle->get_status ();
886+ handle->is_feedback_aware ();
887+ handle->is_result_aware ();
888+
889+ response_callback_called = true ;
890+ };
891+ ops.result_callback = [&result_callback_called](
892+ const GoalHandle::WrappedResult &) {
893+ result_callback_called = true ;
894+ };
895+
896+
897+ goal.order = 6 ;
898+ auto future_goal_handle = action_client->async_send_goal (goal, ops);
899+ dual_spin_until_future_complete (future_goal_handle);
900+ auto goal_handle = future_goal_handle.get ();
901+
902+ ASSERT_TRUE (goal_handle);
903+
904+ ASSERT_EQ (RCL_RET_OK, rcl_set_ros_time_override (clock.get_clock_handle (), RCL_S_TO_NS (2 )));
905+
906+ auto result_future = action_client->async_get_result (goal_handle);
907+ dual_spin_until_future_complete (result_future);
908+
909+ EXPECT_TRUE (result_future.valid ());
910+ auto result = result_future.get ();
911+
912+ test_done = true ;
913+ });
914+
915+ auto curTime = std::chrono::system_clock::now ();
916+
917+ while (std::chrono::system_clock::now () - curTime < std::chrono::milliseconds (500 ) &&
918+ !test_done)
919+ {
920+ std::this_thread::sleep_for (std::chrono::milliseconds (10 ));
921+ }
922+
923+ // in case of a failure, we don't want to block further tests
924+ tr.detach ();
925+
926+ EXPECT_TRUE (test_done);
927+ EXPECT_TRUE (response_callback_called);
928+ EXPECT_TRUE (result_callback_called);
929+ EXPECT_TRUE (feedback_callback_called);
930+ }
931+
855932TEST_F (TestClientAgainstServer, send_rcl_errors)
856933{
857934 auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
0 commit comments