205 moveit_msgs::msg::RobotTrajectory & computedJointTrajectory)
212 if (trajectoryPlanner !=
nullptr)
217 "[CbMoveEndEffectorTrajectory] Using CpJointSpaceTrajectoryPlanner component for IK "
218 "trajectory generation");
234 computedJointTrajectory = result.trajectory;
237 "[CbMoveEndEffectorTrajectory] IK trajectory generation succeeded (via "
238 "CpJointSpaceTrajectoryPlanner)");
243 computedJointTrajectory = result.trajectory;
246 "[CbMoveEndEffectorTrajectory] IK trajectory generation failed (via "
247 "CpJointSpaceTrajectoryPlanner): %s",
248 result.errorMessage.c_str());
251 switch (result.errorCode)
267 "[CbMoveEndEffectorTrajectory] CpJointSpaceTrajectoryPlanner component not available, "
268 "using legacy IK trajectory generation (consider adding CpJointSpaceTrajectoryPlanner "
272 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] getting current state.. waiting");
277 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] getting joint names");
278 auto currentjointnames =
279 currentState->getJointModelGroup(groupname)->getActiveJointModelNames();
286 std::vector<double> jointPositions;
287 currentState->copyJointGroupPositions(groupname, jointPositions);
289 std::vector<std::vector<double>> trajectory;
290 std::vector<rclcpp::Duration> trajectoryTimeStamps;
292 trajectory.push_back(jointPositions);
293 trajectoryTimeStamps.push_back(rclcpp::Duration(0s));
296 rclcpp::Time referenceTime(first.header.stamp);
298 std::vector<int> discontinuityIndexes;
304 auto req = std::make_shared<moveit_msgs::srv::GetPositionIK::Request>();
306 req->ik_request.ik_link_name = *
tipLink_;
307 req->ik_request.robot_state.joint_state.name = currentjointnames;
308 req->ik_request.robot_state.joint_state.position = jointPositions;
309 req->ik_request.group_name = groupname;
310 req->ik_request.avoid_collisions =
true;
311 req->ik_request.pose_stamped = pose;
313 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] IK request: " << k <<
" " << *req);
315 auto resfut =
iksrv_->async_send_request(req);
316 auto status = resfut.wait_for(3s);
318 if (status == std::future_status::ready)
320 auto & prevtrajpoint = trajectory.back();
321 auto res = resfut.get();
323 std::stringstream ss;
324 for (
size_t j = 0; j < res->solution.joint_state.position.size(); j++)
326 auto & jointname = res->solution.joint_state.name[j];
327 auto it = std::find(currentjointnames.begin(), currentjointnames.end(), jointname);
328 if (it != currentjointnames.end())
330 int index = std::distance(currentjointnames.begin(), it);
331 jointPositions[index] = res->solution.joint_state.position[j];
332 ss << jointname <<
"(" << index <<
"): " << jointPositions[index] << std::endl;
337 size_t jointindex = 0;
338 int discontinuityJointIndex = -1;
339 double discontinuityDeltaJointIndex = -1;
344 !(*allowInitialTrajectoryStateJointDiscontinuity_));
347 for (jointindex = 0; jointindex < jointPositions.size(); jointindex++)
349 deltajoint = jointPositions[jointindex] - prevtrajpoint[jointindex];
350 if (fabs(deltajoint) > 0.3)
352 discontinuityDeltaJointIndex = deltajoint;
353 discontinuityJointIndex = jointindex;
358 if (ikAttempts > 0 && discontinuityJointIndex != -1)
366 bool discontinuity =
false;
369 discontinuityIndexes.push_back(k);
370 discontinuity =
true;
375 if (discontinuity && discontinuityJointIndex != -1)
377 std::stringstream ss;
379 << currentjointnames[discontinuityJointIndex]
380 <<
" IK discontinuity : " << discontinuityDeltaJointIndex << std::endl
381 <<
"prev joint value: " << prevtrajpoint[discontinuityJointIndex] << std::endl
382 <<
"current joint value: " << jointPositions[discontinuityJointIndex] << std::endl;
385 for (
size_t ji = 0; ji < jointPositions.size(); ji++)
387 ss << currentjointnames[ji] <<
": " << jointPositions[ji] << std::endl;
390 for (
size_t kindex = 0; kindex < trajectory.size(); kindex++)
392 ss <<
"[" << kindex <<
"]: " << trajectory[kindex][discontinuityJointIndex]
399 <<
"This is the first posture of the trajectory. Maybe the robot initial posture "
401 "not coincident to the initial posture of the generated joint trajectory."
405 RCLCPP_ERROR_STREAM(
getLogger(), ss.str());
407 trajectory.push_back(jointPositions);
408 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
409 trajectoryTimeStamps.push_back(durationFromStart);
414 trajectory.push_back(jointPositions);
415 rclcpp::Duration durationFromStart = rclcpp::Time(pose.header.stamp) - referenceTime;
416 trajectoryTimeStamps.push_back(durationFromStart);
418 RCLCPP_DEBUG_STREAM(
getLogger(),
"IK solution: " << res->solution.joint_state);
419 RCLCPP_DEBUG_STREAM(
getLogger(),
"trajpoint: " << std::endl << ss.str());
429 computedJointTrajectory.joint_trajectory.joint_names = currentjointnames;
431 for (
auto & p : trajectory)
439 trajectory_msgs::msg::JointTrajectoryPoint jp;
441 jp.time_from_start = trajectoryTimeStamps[i];
442 computedJointTrajectory.joint_trajectory.points.push_back(jp);
446 if (discontinuityIndexes.size())
448 if (discontinuityIndexes[0] == 0)
536 tf2::Transform localdirection;
537 localdirection.setIdentity();
538 localdirection.setOrigin(tf2::Vector3(0.05, 0, 0));
543 visualization_msgs::msg::Marker marker;
544 marker.header.frame_id = frameid;
545 marker.header.stamp =
getNode()->now();
546 marker.ns =
"trajectory";
548 marker.type = visualization_msgs::msg::Marker::ARROW;
549 marker.action = visualization_msgs::msg::Marker::ADD;
550 marker.scale.x = 0.005;
551 marker.scale.y = 0.01;
552 marker.scale.z = 0.01;
553 marker.color.a = 0.8;
554 marker.color.r = 1.0;
558 geometry_msgs::msg::Point start, end;
563 tf2::Transform basetransform;
564 tf2::fromMsg(pose.pose, basetransform);
567 end.x = localdirection.getOrigin().x();
568 end.y = localdirection.getOrigin().y();
569 end.z = localdirection.getOrigin().z();
571 marker.pose.position = pose.pose.position;
572 marker.pose.orientation = pose.pose.orientation;
573 marker.points.push_back(start);
574 marker.points.push_back(end);
587 std::string globalFrame, tf2::Stamped<tf2::Transform> & currentEndEffectorTransform)
600 if (tfListener !=
nullptr)
606 tf2::fromMsg(transformOpt.value(), currentEndEffectorTransform);
612 <<
" to " << globalFrame);
620 <<
"] CpTfListener component not available, using legacy TF2 (consider "
621 "adding CpTfListener component)");
622 tf2_ros::Buffer tfBuffer(
getNode()->get_clock());
623 tf2_ros::TransformListener tfListenerLegacy(tfBuffer);
626 tfBuffer.lookupTransform(globalFrame, *
tipLink_, rclcpp::Time(0), rclcpp::Duration(10s)),
627 currentEndEffectorTransform);
630 catch (
const std::exception & e)
633 getLogger(),
"[" <<
getName() <<
"] Exception in getCurrentEndEffectorPose: " << e.what());