37 #ifndef MOVEIT_PR2_ARM_IK_UTILS_ 38 #define MOVEIT_PR2_ARM_IK_UTILS_ 44 #include <kdl/frames.hpp> 45 #include <kdl/jntarray.hpp> 46 #include <kdl/tree.hpp> 53 #include <moveit_msgs/GetPositionFK.h> 54 #include <moveit_msgs/GetPositionIK.h> 55 #include <moveit_msgs/KinematicSolverInfo.h> 66 double distance(
const urdf::Pose &transform);
84 std::string &xml_string);
87 const std::string &root_name,
88 const std::string &tip_name,
92 const std::string &root_name,
93 const std::string &tip_name,
97 const moveit_msgs::KinematicSolverInfo &chain_info);
100 const moveit_msgs::KinematicSolverInfo &chain_info);
103 const moveit_msgs::KinematicSolverInfo &chain_info);
106 const moveit_msgs::KinematicSolverInfo &chain_info);
109 moveit_msgs::GetPositionFK::Response &response,
110 const moveit_msgs::KinematicSolverInfo &chain_info);
113 moveit_msgs::GetPositionIK::Response &response,
114 const moveit_msgs::KinematicSolverInfo &chain_info);
117 const moveit_msgs::KinematicSolverInfo &chain_info);
121 const std::string &root_frame,
125 geometry_msgs::PoseStamped &pose_msg_out,
126 const std::string &root_frame,
130 const std::string &name);
133 moveit_msgs::KinematicSolverInfo &chain_info);
136 #endif// PR2_ARM_IK_UTILS_H
void loadRobotModel(urdf::ModelInterfaceSharedPtr &robot_model_out)
Namespace for the PR2ArmKinematics.
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)
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, geometry_msgs::PoseStamped &pose_msg_out, const std::string &root_frame, tf::TransformListener &tf)
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 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 checkRobotState(moveit_msgs::RobotState &robot_state, const moveit_msgs::KinematicSolverInfo &chain_info)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::Affine3f KDLToEigenMatrix(const KDL::Frame &p)
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool checkLinkNames(const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info)
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)