36 #include <kdl/tree.hpp>
46 const std::string& group_name,
47 const std::string& base_name,
48 const std::string& tip_name,
49 double search_discretization)
51 std::vector<std::string> tip_names = {tip_name};
52 setValues(robot_description, group_name, base_name, tip_names, search_discretization);
59 std::string urdf_xml, full_urdf_xml;
60 node_handle.param(
"urdf_xml", urdf_xml, robot_description);
61 node_handle.searchParam(urdf_xml, full_urdf_xml);
64 if (!node_handle.getParam(full_urdf_xml, xml_string))
66 ROS_FATAL_NAMED(
"trac_ik",
"Could not load the xml from parameter server: %s", urdf_xml.c_str());
70 node_handle.param(full_urdf_xml, xml_string, std::string());
79 ROS_FATAL(
"Failed to extract kdl tree from xml robot description");
83 if (!tree.getChain(base_name, tip_name,
chain))
85 ROS_FATAL(
"Couldn't find chain %s to %s", base_name.c_str(), tip_name.c_str());
91 std::vector<KDL::Segment> chain_segs =
chain.segments;
93 urdf::JointConstSharedPtr joint;
95 std::vector<double> l_bounds, u_bounds;
101 for (
unsigned int i = 0; i < chain_segs.size(); ++i)
105 joint = robot_model.getJoint(chain_segs[i].getJoint().
getName());
106 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
113 if (joint->type != urdf::Joint::CONTINUOUS)
117 lower = std::max(joint->limits->lower, joint->safety->soft_lower_limit);
118 upper = std::min(joint->limits->upper, joint->safety->soft_upper_limit);
122 lower = joint->limits->lower;
123 upper = joint->limits->upper;
138 joint_min(joint_num - 1) = std::numeric_limits<float>::lowest();
139 joint_max(joint_num - 1) = std::numeric_limits<float>::max();
145 ROS_INFO_NAMED(
"trac-ik plugin",
"Looking in common namespaces for param name: %s", (group_name +
"/position_only_ik").c_str());
147 ROS_INFO_NAMED(
"trac-ik plugin",
"Looking in common namespaces for param name: %s", (group_name +
"/solve_type").c_str());
159 while (i < (
int)
chain.getNrOfSegments())
161 if (
chain.getSegment(i).getName() == name)
172 const std::vector<double> &joint_angles,
173 std::vector<geometry_msgs::Pose> &poses)
const
180 poses.resize(link_names.size());
188 geometry_msgs::PoseStamped pose;
194 jnt_pos_in(i) = joint_angles[i];
197 KDL::ChainFkSolverPos_recursive fk_solver(
chain);
200 for (
unsigned int i = 0; i < poses.size(); i++)
209 ROS_ERROR_NAMED(
"trac_ik",
"Could not compute FK for %s", link_names[i].c_str());
219 const std::vector<double> &ik_seed_state,
220 std::vector<double> &solution,
221 moveit_msgs::MoveItErrorCodes &error_code,
225 std::vector<double> consistency_limits;
238 const std::vector<double> &ik_seed_state,
240 std::vector<double> &solution,
241 moveit_msgs::MoveItErrorCodes &error_code,
245 std::vector<double> consistency_limits;
258 const std::vector<double> &ik_seed_state,
260 const std::vector<double> &consistency_limits,
261 std::vector<double> &solution,
262 moveit_msgs::MoveItErrorCodes &error_code,
277 const std::vector<double> &ik_seed_state,
279 std::vector<double> &solution,
280 const IKCallbackFn &solution_callback,
281 moveit_msgs::MoveItErrorCodes &error_code,
284 std::vector<double> consistency_limits;
296 const std::vector<double> &ik_seed_state,
298 const std::vector<double> &consistency_limits,
299 std::vector<double> &solution,
300 const IKCallbackFn &solution_callback,
301 moveit_msgs::MoveItErrorCodes &error_code,
315 const std::vector<double> &ik_seed_state,
317 std::vector<double> &solution,
318 const IKCallbackFn &solution_callback,
319 moveit_msgs::MoveItErrorCodes &error_code,
320 const std::vector<double> &consistency_limits,
328 error_code.val = error_code.NO_IK_SOLUTION;
335 error_code.val = error_code.NO_IK_SOLUTION;
345 in(z) = ik_seed_state[
z];
347 KDL::Twist bounds = KDL::Twist::Zero();
351 bounds.rot.x(std::numeric_limits<float>::max());
352 bounds.rot.y(std::numeric_limits<float>::max());
353 bounds.rot.z(std::numeric_limits<float>::max());
377 int rc = ik_solver.CartToJnt(in, frame, out, bounds);
385 solution[z] = out(z);
388 if (!solution_callback.empty())
390 solution_callback(ik_pose, solution, error_code);
391 if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
406 error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;