@@ -341,25 +341,23 @@ void ComputeIK::compute() {
341
341
marker.color .a *= 0.5 ;
342
342
eef_markers.push_back (marker);
343
343
};
344
- auto const & connected_parent_link_model = moveit::core::RobotModel::getRigidlyConnectedParentLinkModel (link );
345
- if (connected_parent_link_model && connected_parent_link_model->getParentJointModel ()) {
346
- const auto & links_to_visualize = connected_parent_link_model->getParentJointModel ()->getDescendantLinkModels ();
347
- if (colliding) {
348
- SubTrajectory solution;
349
- std::copy (frame_markers.begin (), frame_markers.end (), std::back_inserter (solution.markers ()));
350
- generateCollisionMarkers (sandbox_state, appender, links_to_visualize);
351
- std::copy (eef_markers.begin (), eef_markers.end (), std::back_inserter (solution.markers ()));
352
- solution.markAsFailure ();
353
- // TODO: visualize collisions
354
- solution.setComment (s.comment () + " eef in collision: " + listCollisionPairs (collisions.contacts , " , " ));
355
- auto colliding_scene{ scene->diff () };
356
- colliding_scene->setCurrentState (sandbox_state);
357
- spawn (InterfaceState (colliding_scene), std::move (solution));
358
- return ;
359
- } else {
360
- generateVisualMarkers (sandbox_state, appender, links_to_visualize);
361
- }
362
- }
344
+ const auto & links_to_visualize = moveit::core::RobotModel::getRigidlyConnectedParentLinkModel (link )
345
+ ->getParentJointModel ()
346
+ ->getDescendantLinkModels ();
347
+ if (colliding) {
348
+ SubTrajectory solution;
349
+ std::copy (frame_markers.begin (), frame_markers.end (), std::back_inserter (solution.markers ()));
350
+ generateCollisionMarkers (sandbox_state, appender, links_to_visualize);
351
+ std::copy (eef_markers.begin (), eef_markers.end (), std::back_inserter (solution.markers ()));
352
+ solution.markAsFailure ();
353
+ // TODO: visualize collisions
354
+ solution.setComment (s.comment () + " eef in collision: " + listCollisionPairs (collisions.contacts , " , " ));
355
+ auto colliding_scene{ scene->diff () };
356
+ colliding_scene->setCurrentState (sandbox_state);
357
+ spawn (InterfaceState (colliding_scene), std::move (solution));
358
+ return ;
359
+ } else
360
+ generateVisualMarkers (sandbox_state, appender, links_to_visualize);
363
361
364
362
// determine joint values of robot pose to compare IK solution with for costs
365
363
std::vector<double > compare_pose;
0 commit comments