Skip to content

Commit

Permalink
Small fixes to flaky MoveIt Servo integration tests (#2962)
Browse files Browse the repository at this point in the history
* Remove node in teardown of flaky MoveIt Servo test fixture

* No need for executor to be a shared pointer

* Use explicit executor in CPP integration test as well

* Fix frame names in static transform publisher

* Revert some things that did not help.
  • Loading branch information
sea-bass authored Aug 11, 2024
1 parent 4fad0d0 commit aece55c
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ def generate_test_description():
package="tf2_ros",
plugin="tf2_ros::StaticTransformBroadcasterNode",
name="static_tf2_broadcaster",
parameters=[{"/child_frame_id": "panda_link0", "/frame_id": "world"}],
parameters=[{"child_frame_id": "/panda_link0", "frame_id": "/world"}],
),
],
output="screen",
Expand Down
12 changes: 6 additions & 6 deletions moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,6 @@ class ServoRosFixture : public testing::Test
{
// Create a node to be given to Servo.
servo_test_node_ = std::make_shared<rclcpp::Node>("moveit_servo_test");
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

status_ = moveit_servo::StatusCode::INVALID;

Expand All @@ -96,13 +95,14 @@ class ServoRosFixture : public testing::Test

waitForService();

executor_->add_node(servo_test_node_);
executor_thread_ = std::thread([this]() { executor_->spin(); });
executor_.add_node(servo_test_node_);
executor_thread_ = std::thread([this]() { executor_.spin(); });
}

void TearDown() override
{
executor_->cancel();
executor_.remove_node(servo_test_node_);
executor_.cancel();
if (executor_thread_.joinable())
{
executor_thread_.join();
Expand All @@ -122,7 +122,7 @@ class ServoRosFixture : public testing::Test

rclcpp::sleep_for(std::chrono::milliseconds(500));
}
RCLCPP_INFO(logger, "SERVICE READY");
RCLCPP_INFO(logger, "MoveIt Servo input switching service ready!");
}

void waitForJointStates()
Expand Down Expand Up @@ -150,7 +150,7 @@ class ServoRosFixture : public testing::Test
std::shared_ptr<rclcpp::Node> servo_test_node_;

// Executor and a thread to run the executor.
rclcpp::Executor::SharedPtr executor_;
rclcpp::executors::SingleThreadedExecutor executor_;
std::thread executor_thread_;

rclcpp::Subscription<moveit_msgs::msg::ServoStatus>::SharedPtr status_subscriber_;
Expand Down

0 comments on commit aece55c

Please sign in to comment.