@@ -314,6 +314,11 @@ void ComputeIK::compute() {
314
314
315
315
link = scene->getCurrentState ().getRigidlyConnectedParentLinkModel (ik_pose_msg.header .frame_id );
316
316
317
+ if (!link ) {
318
+ RCLCPP_WARN_STREAM (
319
+ LOGGER, fmt::format (" ik frame '{}' is not rigidly connected to any link" , ik_pose_msg.header .frame_id ));
320
+ return ;
321
+ }
317
322
// transform target pose such that ik frame will reach there if link does
318
323
target_pose = target_pose * ik_pose.inverse () * scene->getCurrentState ().getFrameTransform (link ->getName ());
319
324
}
@@ -336,23 +341,25 @@ void ComputeIK::compute() {
336
341
marker.color .a *= 0.5 ;
337
342
eef_markers.push_back (marker);
338
343
};
339
- const auto & links_to_visualize = moveit::core::RobotModel::getRigidlyConnectedParentLinkModel (link )
340
- ->getParentJointModel ()
341
- ->getDescendantLinkModels ();
342
- if (colliding) {
343
- SubTrajectory solution;
344
- std::copy (frame_markers.begin (), frame_markers.end (), std::back_inserter (solution.markers ()));
345
- generateCollisionMarkers (sandbox_state, appender, links_to_visualize);
346
- std::copy (eef_markers.begin (), eef_markers.end (), std::back_inserter (solution.markers ()));
347
- solution.markAsFailure ();
348
- // TODO: visualize collisions
349
- solution.setComment (s.comment () + " eef in collision: " + listCollisionPairs (collisions.contacts , " , " ));
350
- auto colliding_scene{ scene->diff () };
351
- colliding_scene->setCurrentState (sandbox_state);
352
- spawn (InterfaceState (colliding_scene), std::move (solution));
353
- return ;
354
- } else
355
- generateVisualMarkers (sandbox_state, appender, links_to_visualize);
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
+ }
356
363
357
364
// determine joint values of robot pose to compare IK solution with for costs
358
365
std::vector<double > compare_pose;
0 commit comments