45 std::string urdf_xml, full_urdf_xml;
46 node_handle.
param(
"urdf_xml", urdf_xml, std::string(
"robot_description"));
49 ROS_DEBUG(
"Reading xml file from parameter server\n");
51 if (node_handle.
getParam(full_urdf_xml, result))
52 xml.Parse(result.c_str());
55 ROS_FATAL(
"Could not load the xml from parameter server: %s\n", urdf_xml.c_str());
59 TiXmlElement* root_element = xml.RootElement();
60 TiXmlElement* root = xml.FirstChildElement(
"robot");
61 if (!root || !root_element)
63 ROS_FATAL(
"Could not parse the xml from %s\n", urdf_xml.c_str());
70 bool getKDLChain(
const std::string& xml_string,
const std::string& root_name,
const std::string& tip_name,
77 ROS_ERROR(
"Could not initialize tree object");
80 if (!tree.
getChain(root_name, tip_name, kdl_chain))
82 ROS_ERROR_STREAM(
"Could not initialize chain object for base " << root_name <<
" tip " << tip_name);
88 bool getKDLTree(
const std::string& xml_string,
const std::string& root_name,
const std::string& tip_name,
94 ROS_ERROR(
"Could not initialize tree object");
102 Eigen::Matrix4f b = Eigen::Matrix4f::Identity();
103 for (
int i = 0; i < 3; i++)
105 for (
int j = 0; j < 3; j++)
117 for (
int i = 0; i < (int)array_1.size(); i++)
119 distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i));
121 return sqrt(distance);
124 double distance(
const urdf::Pose& transform)
126 return sqrt(transform.position.x * transform.position.x + transform.position.y * transform.position.y +
127 transform.position.z * transform.position.z);
130 bool solveQuadratic(
const double& a,
const double& b,
const double& c,
double* x1,
double* x2)
132 double discriminant = b * b - 4 * a * c;
140 if (discriminant >= 0)
142 *x1 = (-b +
sqrt(discriminant)) / (2 * a);
143 *x2 = (-b -
sqrt(discriminant)) / (2 * a);
146 else if (fabs(discriminant) <
IK_EPS)
162 Eigen::Matrix4f result = g;
163 Eigen::Matrix3f Rt = Eigen::Matrix3f::Identity();
165 Eigen::Vector3f p = Eigen::Vector3f::Zero(3);
166 Eigen::Vector3f pinv = Eigen::Vector3f::Zero(3);
187 result(0, 0) = g(0, 0);
188 result(1, 1) = g(1, 1);
189 result(2, 2) = g(2, 2);
191 result(0, 1) = g(1, 0);
192 result(1, 0) = g(0, 1);
194 result(0, 2) = g(2, 0);
195 result(2, 0) = g(0, 2);
197 result(1, 2) = g(2, 1);
198 result(2, 1) = g(1, 2);
200 result(0, 3) = pinv(0);
201 result(1, 3) = pinv(1);
202 result(2, 3) = pinv(2);
207 bool solveCosineEqn(
const double& a,
const double& b,
const double& c,
double& soln1,
double& soln2)
209 double theta1 =
atan2(b, a);
210 double denom =
sqrt(a * a + b * b);
215 std::cout <<
"denom: " << denom << std::endl;
219 double rhs_ratio = c / denom;
220 if (rhs_ratio < -1 || rhs_ratio > 1)
223 std::cout <<
"rhs_ratio: " << rhs_ratio << std::endl;
227 double acos_term =
acos(rhs_ratio);
228 soln1 = theta1 + acos_term;
229 soln2 = theta1 - acos_term;
234 bool checkJointNames(
const std::vector<std::string>& joint_names,
const moveit_msgs::KinematicSolverInfo& chain_info)
236 for (
unsigned int i = 0; i < chain_info.joint_names.size(); i++)
239 for (
unsigned int j = 0; j < joint_names.size(); j++)
241 if (chain_info.joint_names[i] == joint_names[j])
249 ROS_ERROR(
"Joint state does not contain joint state for %s.", chain_info.joint_names[i].c_str());
256 bool checkLinkNames(
const std::vector<std::string>& link_names,
const moveit_msgs::KinematicSolverInfo& chain_info)
258 if (link_names.empty())
260 for (
unsigned int i = 0; i < link_names.size(); i++)
268 bool checkLinkName(
const std::string& link_name,
const moveit_msgs::KinematicSolverInfo& chain_info)
270 for (
unsigned int i = 0; i < chain_info.link_names.size(); i++)
272 if (link_name == chain_info.link_names[i])
278 bool checkRobotState(moveit_msgs::RobotState& robot_state,
const moveit_msgs::KinematicSolverInfo& chain_info)
280 if ((
int)robot_state.joint_state.position.size() != (int)robot_state.joint_state.name.size())
283 "Number of joints in robot_state.joint_state does not match number of positions in robot_state.joint_state");
288 ROS_ERROR(
"Robot state must contain joint state for every joint in the kinematic chain");
294 bool checkFKService(moveit_msgs::GetPositionFK::Request& request, moveit_msgs::GetPositionFK::Response& response,
295 const moveit_msgs::KinematicSolverInfo& chain_info)
299 ROS_ERROR(
"Link name in service request does not match links that kinematics can provide solutions for.");
300 response.error_code.val = response.error_code.INVALID_LINK_NAME;
305 response.error_code.val = response.error_code.INVALID_ROBOT_STATE;
311 bool checkIKService(moveit_msgs::GetPositionIK::Request& request, moveit_msgs::GetPositionIK::Response& response,
312 const moveit_msgs::KinematicSolverInfo& chain_info)
314 if (!
checkLinkName(request.ik_request.ik_link_name, chain_info))
316 ROS_ERROR(
"Link name in service request does not match links that kinematics can provide solutions for.");
317 response.error_code.val = response.error_code.INVALID_LINK_NAME;
322 response.error_code.val = response.error_code.INVALID_ROBOT_STATE;
327 response.error_code.val = response.error_code.TIMED_OUT;
336 geometry_msgs::PoseStamped pose_stamped;
346 geometry_msgs::PoseStamped pose_msg_in = pose_msg;
347 ROS_DEBUG(
"Request:\nframe_id: %s\nPosition: %f %f %f\n:Orientation: %f %f %f %f\n",
348 pose_msg_in.header.frame_id.c_str(), pose_msg_in.pose.position.x, pose_msg_in.pose.position.y,
349 pose_msg_in.pose.position.z, pose_msg_in.pose.orientation.x, pose_msg_in.pose.orientation.y,
350 pose_msg_in.pose.orientation.z, pose_msg_in.pose.orientation.w);
351 pose_msg_out = pose_msg;
353 poseStampedMsgToTF(pose_msg_in, pose_stamped);
360 ROS_ERROR(
"pr2_arm_ik:: Cannot transform from '%s' to '%s'. TF said: %s", pose_stamped.
frame_id_.c_str(),
361 root_frame.c_str(), err.c_str());
371 ROS_ERROR(
"pr2_arm_ik:: Cannot transform from '%s' to '%s'", pose_stamped.
frame_id_.c_str(), root_frame.c_str());
378 int getJointIndex(
const std::string& name,
const moveit_msgs::KinematicSolverInfo& chain_info)
380 for (
unsigned int i = 0; i < chain_info.joint_names.size(); i++)
382 if (chain_info.joint_names[i] == name)
static const double IK_DEFAULT_TIMEOUT
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
Namespace for the PR2ArmKinematics.
unsigned int getNrOfSegments() const
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
const Segment & getSegment(unsigned int nr) const
bool checkJointNames(const std::vector< std::string > &joint_names, const moveit_msgs::KinematicSolverInfo &chain_info)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, KDL::Frame &pose_kdl, const std::string &root_frame, tf::TransformListener &tf)
bool checkIKService(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool checkLinkName(const std::string &link_name, const moveit_msgs::KinematicSolverInfo &chain_info)
bool getParam(const std::string &key, std::string &s) const
bool checkRobotState(moveit_msgs::RobotState &robot_state, const moveit_msgs::KinematicSolverInfo &chain_info)
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
KDL_PARSER_PUBLIC bool treeFromString(const std::string &xml, KDL::Tree &tree)
URDF_EXPORT bool initXml(const tinyxml2::XMLElement *xml)
bool searchParam(const std::string &key, std::string &result) const
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
const std::string & getName() const
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
static const double IK_EPS
#define ROS_ERROR_STREAM(args)
bool checkLinkNames(const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
double distance(const urdf::Pose &transform)
Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f &g)
bool getKDLTree(const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Tree &kdl_chain)
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)