Go to the documentation of this file.
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>
65 const KDL::JntArray &array_2);
67 double distance(
const urdf::Pose &transform);
85 std::string &xml_string);
88 const std::string &root_name,
89 const std::string &tip_name,
90 KDL::Chain &kdl_chain);
93 const std::string &root_name,
94 const std::string &tip_name,
95 KDL::Tree &kdl_chain);
98 const moveit_msgs::KinematicSolverInfo &chain_info);
101 const moveit_msgs::KinematicSolverInfo &chain_info);
104 const moveit_msgs::KinematicSolverInfo &chain_info);
107 const moveit_msgs::KinematicSolverInfo &chain_info);
110 moveit_msgs::GetPositionFK::Response &response,
111 const moveit_msgs::KinematicSolverInfo &chain_info);
114 moveit_msgs::GetPositionIK::Response &response,
115 const moveit_msgs::KinematicSolverInfo &chain_info);
118 const moveit_msgs::KinematicSolverInfo &chain_info);
121 KDL::Frame &pose_kdl,
122 const std::string &root_frame,
126 geometry_msgs::PoseStamped &pose_msg_out,
127 const std::string &root_frame,
131 const std::string &name);
134 moveit_msgs::KinematicSolverInfo &chain_info);
137 #endif// PR2_ARM_IK_UTILS_H
Namespace for the PR2ArmKinematics.
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)
bool checkIKService(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, geometry_msgs::PoseStamped &pose_msg_out, const std::string &root_frame, tf::TransformListener &tf)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
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)
bool getKDLTree(const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Tree &kdl_chain)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f &g)
bool checkLinkNames(const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info)
bool checkJointNames(const std::vector< std::string > &joint_names, const moveit_msgs::KinematicSolverInfo &chain_info)