36 #ifndef HAND_KINEMATICS_HAND_KINEMATICS_UTILS_H 37 #define HAND_KINEMATICS_HAND_KINEMATICS_UTILS_H 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> 61 std::string &root_name,
62 std::string &tip_name,
63 std::string &xml_string);
66 const std::string &root_name,
67 const std::string &tip_name,
71 const std::string &root_name,
72 const std::string &tip_name,
76 const moveit_msgs::KinematicSolverInfo &chain_info);
79 const moveit_msgs::KinematicSolverInfo &chain_info);
82 const moveit_msgs::KinematicSolverInfo &chain_info);
85 const moveit_msgs::KinematicSolverInfo &chain_info);
88 moveit_msgs::GetPositionFK::Response &response,
89 const moveit_msgs::KinematicSolverInfo &chain_info);
92 moveit_msgs::GetPositionIK::Response &response,
93 const moveit_msgs::KinematicSolverInfo &chain_info);
96 const moveit_msgs::KinematicSolverInfo &chain_info);
100 const std::string &root_frame,
104 geometry_msgs::PoseStamped &pose_msg_out,
105 const std::string &root_frame,
109 const std::string &name);
112 moveit_msgs::KinematicSolverInfo &chain_info);
114 bool init_ik(
urdf::Model &robot_model,
const std::string &root_name,
const std::string &tip_name,
129 #endif // HAND_KINEMATICS_HAND_KINEMATICS_UTILS_H
bool checkRobotState(moveit_msgs::RobotState &robot_state, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingRF(const KDL::JntArray &q)
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, KDL::Frame &pose_kdl, const std::string &root_frame, tf::TransformListener &tf)
bool checkIKService(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, 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::MatrixXd updateCouplingMF(const KDL::JntArray &q)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingTH(const KDL::JntArray &q)
bool getKDLChain(const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &root_name, std::string &tip_name, std::string &xml_string)
bool checkJointNames(const std::vector< std::string > &joint_names, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingLF(const KDL::JntArray &q)
bool checkLinkName(const std::string &link_name, const moveit_msgs::KinematicSolverInfo &chain_info)
Eigen::MatrixXd updateCouplingFF(const KDL::JntArray &q)
bool checkLinkNames(const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info)
bool init_ik(urdf::Model &robot_model, const std::string &root_name, const std::string &tip_name, KDL::JntArray &joint_min, KDL::JntArray &joint_max, moveit_msgs::KinematicSolverInfo &info)
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)