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 #ifndef PR2_ARM_IK_UTILS_H
00035 #define PR2_ARM_IK_UTILS_H
00036
00037 #include <ros/ros.h>
00038 #include <vector>
00039 #include <angles/angles.h>
00040 #include <Eigen/Array>
00041 #include <kdl/frames.hpp>
00042 #include <kdl/jntarray.hpp>
00043 #include <kdl/tree.hpp>
00044 #include <urdf/model.h>
00045 #include <kdl_parser/kdl_parser.hpp>
00046 #include <tf/tf.h>
00047 #include <tf/transform_listener.h>
00048 #include <tf_conversions/tf_kdl.h>
00049
00050 #include <kinematics_msgs/GetPositionFK.h>
00051 #include <kinematics_msgs/GetPositionIK.h>
00052 #include <kinematics_msgs/GetConstraintAwarePositionIK.h>
00053 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00054
00055
00056 using namespace angles;
00057
00058 namespace pr2_arm_kinematics
00059 {
00060 Eigen::Matrix4f KDLToEigenMatrix(const KDL::Frame &p);
00061
00062 double computeEuclideanDistance(const std::vector<double> &array_1,
00063 const KDL::JntArray &array_2);
00064
00065 double distance(const urdf::Pose &transform);
00066
00067 bool solveQuadratic(const double &a,
00068 const double &b,
00069 const double &c,
00070 double *x1,
00071 double *x2);
00072
00073 Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f &g);
00074
00075 bool solveCosineEqn(const double &a,
00076 const double &b,
00077 const double &c,
00078 double &soln1,
00079 double &soln2);
00080
00081 bool loadRobotModel(ros::NodeHandle node_handle,
00082 urdf::Model &robot_model,
00083 std::string &root_name,
00084 std::string &tip_name,
00085 std::string &xml_string);
00086
00087 bool getKDLChain(const std::string &xml_string,
00088 const std::string &root_name,
00089 const std::string &tip_name,
00090 KDL::Chain &kdl_chain);
00091
00092 bool getKDLTree(const std::string &xml_string,
00093 const std::string &root_name,
00094 const std::string &tip_name,
00095 KDL::Tree &kdl_chain);
00096
00097 bool checkJointNames(const std::vector<std::string> &joint_names,
00098 const kinematics_msgs::KinematicSolverInfo &chain_info);
00099
00100 bool checkLinkNames(const std::vector<std::string> &link_names,
00101 const kinematics_msgs::KinematicSolverInfo &chain_info);
00102
00103 bool checkLinkName(const std::string &link_name,
00104 const kinematics_msgs::KinematicSolverInfo &chain_info);
00105
00106 bool checkRobotState(motion_planning_msgs::RobotState &robot_state,
00107 const kinematics_msgs::KinematicSolverInfo &chain_info);
00108
00109 bool checkFKService(kinematics_msgs::GetPositionFK::Request &request,
00110 kinematics_msgs::GetPositionFK::Response &response,
00111 const kinematics_msgs::KinematicSolverInfo &chain_info);
00112
00113 bool checkIKService(kinematics_msgs::GetPositionIK::Request &request,
00114 kinematics_msgs::GetPositionIK::Response &response,
00115 const kinematics_msgs::KinematicSolverInfo &chain_info);
00116
00117 bool checkConstraintAwareIKService(kinematics_msgs::GetConstraintAwarePositionIK::Request &request,
00118 kinematics_msgs::GetConstraintAwarePositionIK::Response &response,
00119 const kinematics_msgs::KinematicSolverInfo &chain_info);
00120
00121 int getJointIndex(const std::string &name,
00122 const kinematics_msgs::KinematicSolverInfo &chain_info);
00123
00124 bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
00125 KDL::Frame &pose_kdl,
00126 const std::string &root_frame,
00127 const tf::TransformListener &tf);
00128
00129 bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg,
00130 geometry_msgs::PoseStamped &pose_msg_out,
00131 const std::string &root_frame,
00132 const tf::TransformListener &tf);
00133
00134 int getKDLSegmentIndex(const KDL::Chain &chain,
00135 const std::string &name);
00136
00137 void getKDLChainInfo(const KDL::Chain &chain,
00138 kinematics_msgs::KinematicSolverInfo &chain_info);
00139 }
00140
00141 #endif// PR2_ARM_IK_UTILS_H