Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Cleanup #3056 #3058

Merged
merged 4 commits into from
Nov 5, 2024
Merged
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
30 changes: 5 additions & 25 deletions moveit_ros/moveit_servo/tests/servo_cpp_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,24 +61,13 @@ class ServoCppFixture : public testing::Test
servo_params_ = servo_param_listener_->get_params();

planning_scene_monitor_ = moveit_servo::createPlanningSceneMonitor(servo_test_node_, servo_params_);

// Wait until the joint configuration is nonzero before starting MoveIt Servo.
int num_tries = 0;
const int max_tries = 20;
while (true)
// Wait for complete state update before starting MoveIt Servo.
if (!planning_scene_monitor_->getStateMonitor()->waitForCompleteState("panda_arm", 1.0))
{
const auto q = getCurrentJointPositions("panda_arm");
if (q.norm() > 0.0)
{
break;
}
if (num_tries > max_tries)
{
FAIL() << "Robot joint configuration did not reach expected state after some time. Test is flaky.";
}
std::this_thread::sleep_for(std::chrono::milliseconds(100));
num_tries++;
FAIL() << "Could not retrieve complete robot state";
}
// Forward state update to planning scene
planning_scene_monitor_->updateSceneWithCurrentState();

servo_test_instance_ =
std::make_shared<moveit_servo::Servo>(servo_test_node_, servo_param_listener_, planning_scene_monitor_);
Expand All @@ -91,15 +80,6 @@ class ServoCppFixture : public testing::Test
return locked_scene->getCurrentState().getGlobalLinkTransform(target_frame);
}

/// Helper function to get the joint configuration of a group.
Eigen::VectorXd getCurrentJointPositions(const std::string& group_name) const
{
planning_scene_monitor::LockedPlanningSceneRO locked_scene(planning_scene_monitor_);
std::vector<double> joint_positions;
locked_scene->getCurrentState().copyJointGroupPositions(group_name, joint_positions);
return Eigen::Map<Eigen::VectorXd>(joint_positions.data(), joint_positions.size());
}

std::shared_ptr<rclcpp::Node> servo_test_node_;
std::shared_ptr<const servo::ParamListener> servo_param_listener_;
servo::Params servo_params_;
Expand Down
Loading