Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef MOVEIT_PR2_ARM_IK_UTILS_
00040 #define MOVEIT_PR2_ARM_IK_UTILS_
00041
00042 #include <ros/ros.h>
00043 #include <vector>
00044 #include <angles/angles.h>
00045 #include <Eigen/Core>
00046 #include <kdl/frames.hpp>
00047 #include <kdl/jntarray.hpp>
00048 #include <kdl/tree.hpp>
00049 #include <urdf/model.h>
00050 #include <kdl_parser/kdl_parser.hpp>
00051 #include <tf/tf.h>
00052 #include <tf/transform_listener.h>
00053 #include <tf_conversions/tf_kdl.h>
00054
00055 #include <moveit_msgs/GetPositionFK.h>
00056 #include <moveit_msgs/GetPositionIK.h>
00057 #include <moveit_msgs/GetKinematicSolverInfo.h>
00058
00059
00060 using namespace angles;
00061
00062 namespace pr2_arm_kinematics
00063 {
00064 Eigen::Matrix4f KDLToEigenMatrix(const KDL::Frame &p);
00065
00066 double computeEuclideanDistance(const std::vector<double> &array_1,
00067 const KDL::JntArray &array_2);
00068
00069 double distance(const urdf::Pose &transform);
00070
00071 bool solveQuadratic(const double &a,
00072 const double &b,
00073 const double &c,
00074 double *x1,
00075 double *x2);
00076
00077 Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f &g);
00078
00079 bool solveCosineEqn(const double &a,
00080 const double &b,
00081 const double &c,
00082 double &soln1,
00083 double &soln2);
00084
00085 bool loadRobotModel(ros::NodeHandle node_handle,
00086 urdf::Model &robot_model,
00087 std::string &xml_string);
00088
00089 bool getKDLChain(const std::string &xml_string,
00090 const std::string &root_name,
00091 const std::string &tip_name,
00092 KDL::Chain &kdl_chain);
00093
00094 bool getKDLTree(const std::string &xml_string,
00095 const std::string &root_name,
00096 const std::string &tip_name,
00097 KDL::Tree &kdl_chain);
00098
00099 bool checkJointNames(const std::vector<std::string> &joint_names,
00100 const moveit_msgs::KinematicSolverInfo &chain_info);
00101
00102 bool checkLinkNames(const std::vector<std::string> &link_names,
00103 const moveit_msgs::KinematicSolverInfo &chain_info);
00104
00105 bool checkLinkName(const std::string &link_name,
00106 const moveit_msgs::KinematicSolverInfo &chain_info);
00107
00108 bool checkRobotState(moveit_msgs::RobotState &robot_state,
00109 const moveit_msgs::KinematicSolverInfo &chain_info);
00110
00111 bool checkFKService(moveit_msgs::GetPositionFK::Request &request,
00112 moveit_msgs::GetPositionFK::Response &response,
00113 const moveit_msgs::KinematicSolverInfo &chain_info);
00114
00115 bool checkIKService(moveit_msgs::GetPositionIK::Request &request,
00116 moveit_msgs::GetPositionIK::Response &response,
00117 const moveit_msgs::KinematicSolverInfo &chain_info);
00118
00119 int getJointIndex(const std::string &name,
00120 const moveit_msgs::KinematicSolverInfo &chain_info);
00121
00122 bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
00123 KDL::Frame &pose_kdl,
00124 const std::string &root_frame,
00125 tf::TransformListener& tf);
00126
00127 bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
00128 geometry_msgs::PoseStamped &pose_msg_out,
00129 const std::string &root_frame,
00130 tf::TransformListener& tf);
00131
00132 int getKDLSegmentIndex(const KDL::Chain &chain,
00133 const std::string &name);
00134
00135 void getKDLChainInfo(const KDL::Chain &chain,
00136 moveit_msgs::KinematicSolverInfo &chain_info);
00137 }
00138
00139 #endif// PR2_ARM_IK_UTILS_H