Skip to content

Commit ddfa7ff

Browse files
committed
Cleanup moveit#3056
1 parent b3b1f73 commit ddfa7ff

File tree

1 file changed

+2
-24
lines changed

1 file changed

+2
-24
lines changed

moveit_ros/moveit_servo/tests/servo_cpp_fixture.hpp

Lines changed: 2 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -61,23 +61,10 @@ class ServoCppFixture : public testing::Test
6161
servo_params_ = servo_param_listener_->get_params();
6262

6363
planning_scene_monitor_ = moveit_servo::createPlanningSceneMonitor(servo_test_node_, servo_params_);
64-
6564
// Wait until the joint configuration is nonzero before starting MoveIt Servo.
66-
int num_tries = 0;
67-
const int max_tries = 20;
68-
while (true)
65+
if (!planning_scene_monitor_->getStateMonitor()->waitForCompleteState("panda_arm", 2.0))
6966
{
70-
const auto q = getCurrentJointPositions("panda_arm");
71-
if (q.norm() > 0.0)
72-
{
73-
break;
74-
}
75-
if (num_tries > max_tries)
76-
{
77-
FAIL() << "Robot joint configuration did not reach expected state after some time. Test is flaky.";
78-
}
79-
std::this_thread::sleep_for(std::chrono::milliseconds(100));
80-
num_tries++;
67+
FAIL() << "Could not retrieve complete robot state";
8168
}
8269

8370
servo_test_instance_ =
@@ -91,15 +78,6 @@ class ServoCppFixture : public testing::Test
9178
return locked_scene->getCurrentState().getGlobalLinkTransform(target_frame);
9279
}
9380

94-
/// Helper function to get the joint configuration of a group.
95-
Eigen::VectorXd getCurrentJointPositions(const std::string& group_name) const
96-
{
97-
planning_scene_monitor::LockedPlanningSceneRO locked_scene(planning_scene_monitor_);
98-
std::vector<double> joint_positions;
99-
locked_scene->getCurrentState().copyJointGroupPositions(group_name, joint_positions);
100-
return Eigen::Map<Eigen::VectorXd>(joint_positions.data(), joint_positions.size());
101-
}
102-
10381
std::shared_ptr<rclcpp::Node> servo_test_node_;
10482
std::shared_ptr<const servo::ParamListener> servo_param_listener_;
10583
servo::Params servo_params_;

0 commit comments

Comments
 (0)