62 const double* ik_solution)
82 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
84 if (req.pose_stamped_vector.empty() || req.pose_stamped_vector.size() == 1)
86 geometry_msgs::PoseStamped req_pose =
87 req.pose_stamped_vector.empty() ? req.pose_stamped : req.pose_stamped_vector[0];
88 std::string ik_link = (!req.pose_stamped_vector.empty()) ?
89 (req.ik_link_names.empty() ?
"" : req.ik_link_names[0]) :
94 bool result_ik =
false;
96 result_ik = rs.
setFromIK(jmg, req_pose.pose, req.timeout.toSec(), constraint);
98 result_ik = rs.
setFromIK(jmg, req_pose.pose, ik_link, req.timeout.toSec(), constraint);
103 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
106 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
109 error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
113 if (req.pose_stamped_vector.size() != req.ik_link_names.size())
114 error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME;
119 for (std::size_t k = 0; k < req.pose_stamped_vector.size(); ++k)
121 geometry_msgs::PoseStamped msg = req.pose_stamped_vector[k];
126 error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
133 if (rs.
setFromIK(jmg, req_poses, req.ik_link_names, req.timeout.toSec(), constraint))
136 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
139 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
145 error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
149 moveit_msgs::GetPositionIK::Response& res)
151 context_->planning_scene_monitor_->updateFrameTransforms();
159 kset.add(req.ik_request.constraints, ls->getTransforms());
160 computeIK(req.ik_request, res.solution, res.error_code, rs,
161 [scene = req.ik_request.avoid_collisions ?
162 static_cast<const planning_scene::PlanningSceneConstPtr&
>(ls).get() :
166 const double* joint_group_variable_values) {
167 return isIKSolutionValid(scene, kset_ptr, robot_state, joint_group, joint_group_variable_values);
175 computeIK(req.ik_request, res.solution, res.error_code, rs);
182 moveit_msgs::GetPositionFK::Response& res)
184 if (req.fk_link_names.empty())
187 res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME;
191 context_->planning_scene_monitor_->updateFrameTransforms();
193 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
194 bool do_transform = !req.header.frame_id.empty() &&
196 context_->planning_scene_monitor_->getTFClient();
197 bool tf_problem =
false;
202 for (std::size_t i = 0; i < req.fk_link_names.size(); ++i)
205 res.pose_stamped.resize(res.pose_stamped.size() + 1);
207 res.pose_stamped.back().header.frame_id = default_frame;
212 res.fk_link_names.push_back(req.fk_link_names[i]);
215 res.error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
216 else if (res.fk_link_names.size() == req.fk_link_names.size())
217 res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
219 res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME;