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