@@ -61,24 +61,13 @@ class ServoCppFixture : public testing::Test
61
61
servo_params_ = servo_param_listener_->get_params ();
62
62
63
63
planning_scene_monitor_ = moveit_servo::createPlanningSceneMonitor (servo_test_node_, servo_params_);
64
-
65
- // 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 )
64
+ // Wait for complete state update before starting MoveIt Servo.
65
+ if (!planning_scene_monitor_->getStateMonitor ()->waitForCompleteState (" panda_arm" , 1.0 ))
69
66
{
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" ;
81
68
}
69
+ // Forward state update to planning scene
70
+ planning_scene_monitor_->updateSceneWithCurrentState ();
82
71
83
72
servo_test_instance_ =
84
73
std::make_shared<moveit_servo::Servo>(servo_test_node_, servo_param_listener_, planning_scene_monitor_);
@@ -91,15 +80,6 @@ class ServoCppFixture : public testing::Test
91
80
return locked_scene->getCurrentState ().getGlobalLinkTransform (target_frame);
92
81
}
93
82
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
-
103
83
std::shared_ptr<rclcpp::Node> servo_test_node_;
104
84
std::shared_ptr<const servo::ParamListener> servo_param_listener_;
105
85
servo::Params servo_params_;
0 commit comments