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 double distance(
const urdf::Pose& transform);
67 bool solveQuadratic(
const double& a,
const double& b,
const double& c,
double* x1,
double* x2);
71 bool solveCosineEqn(
const double& a,
const double& b,
const double& c,
double& soln1,
double& soln2);
75 bool getKDLChain(
const std::string& xml_string,
const std::string& root_name,
const std::string& tip_name,
78 bool getKDLTree(
const std::string& xml_string,
const std::string& root_name,
const std::string& tip_name,
81 bool checkJointNames(
const std::vector<std::string>& joint_names,
const moveit_msgs::KinematicSolverInfo& chain_info);
83 bool checkLinkNames(
const std::vector<std::string>& link_names,
const moveit_msgs::KinematicSolverInfo& chain_info);
85 bool checkLinkName(
const std::string& link_name,
const moveit_msgs::KinematicSolverInfo& chain_info);
87 bool checkRobotState(moveit_msgs::RobotState& robot_state,
const moveit_msgs::KinematicSolverInfo& chain_info);
89 bool checkFKService(moveit_msgs::GetPositionFK::Request& request, moveit_msgs::GetPositionFK::Response& response,
90 const moveit_msgs::KinematicSolverInfo& chain_info);
92 bool checkIKService(moveit_msgs::GetPositionIK::Request& request, moveit_msgs::GetPositionIK::Response& response,
93 const moveit_msgs::KinematicSolverInfo& chain_info);
95 int getJointIndex(
const std::string& name,
const moveit_msgs::KinematicSolverInfo& chain_info);
100 bool convertPoseToRootFrame(
const geometry_msgs::PoseStamped& pose_msg, geometry_msgs::PoseStamped& pose_msg_out,
108 #endif // PR2_ARM_IK_UTILS_H
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)
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)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
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)
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)