From 5483824685b6482585b1a0a8b50644dfb5c4fab7 Mon Sep 17 00:00:00 2001 From: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Date: Tue, 8 Aug 2023 14:55:46 -0400 Subject: [PATCH] Fix failure in bringup test (#740) --- doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp | 10 +++++++++- .../quickstart_in_rviz/test/bringup_test.test.py | 1 - 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp b/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp index 2fe80a5f20..3597c8e06e 100644 --- a/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp +++ b/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp @@ -5,6 +5,8 @@ #include #include +#include +#include #include #include @@ -71,7 +73,13 @@ TEST_F(BringupTestFixture, BasicBringupTest) }; auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); send_goal_options.result_callback = result_cb; - control_client->async_send_goal(joint_traj_request, send_goal_options); + + // Ensure the status of executing the trajectory is not a timeout. + auto goal_handle_future = control_client->async_send_goal(joint_traj_request, send_goal_options); + ASSERT_NE(goal_handle_future.wait_for(std::chrono::seconds(5)), std::future_status::timeout); + + // Sleeping for a bit helps prevent segfaults when shutting down the control node. + std::this_thread::sleep_for(std::chrono::seconds(1)); } } // namespace moveit2_tutorials::quickstart_in_rviz diff --git a/doc/tutorials/quickstart_in_rviz/test/bringup_test.test.py b/doc/tutorials/quickstart_in_rviz/test/bringup_test.test.py index f1c7972a7e..849628875a 100644 --- a/doc/tutorials/quickstart_in_rviz/test/bringup_test.test.py +++ b/doc/tutorials/quickstart_in_rviz/test/bringup_test.test.py @@ -43,7 +43,6 @@ def generate_test_description(): ), base_launch, # The test itself - bringup_test, TimerAction(period=2.0, actions=[bringup_test]), launch_testing.actions.ReadyToTest(), ]