40 #ifndef HAND_KINEMATICS_HAND_KINEMATICS_PLUGIN_H 41 #define HAND_KINEMATICS_HAND_KINEMATICS_PLUGIN_H 52 #include <kdl/jntarray.hpp> 54 #include <kdl/chainfksolverpos_recursive.hpp> 57 #include <moveit_msgs/KinematicSolverInfo.h> 63 #include <moveit_msgs/MoveItErrorCodes.h> 64 #include <boost/shared_ptr.hpp> 88 virtual bool getPositionIK(
const geometry_msgs::Pose &ik_pose,
89 const std::vector<double> &ik_seed_state,
90 std::vector<double> &solution,
91 moveit_msgs::MoveItErrorCodes &error_code,
96 const std::vector<double> &ik_seed_state,
98 std::vector<double> &solution,
99 moveit_msgs::MoveItErrorCodes &error_code,
105 const std::vector<double> &ik_seed_state,
107 const std::vector<double> &consistency_limits,
108 std::vector<double> &solution,
109 moveit_msgs::MoveItErrorCodes &error_code,
120 const std::vector<double> &ik_seed_state,
122 std::vector<double> &solution,
124 moveit_msgs::MoveItErrorCodes &error_code,
134 const std::vector<double> &ik_seed_state,
136 const std::vector<double> &consistency_limits,
137 std::vector<double> &solution,
139 moveit_msgs::MoveItErrorCodes &error_code,
151 virtual bool getPositionFK(
const std::vector<std::string> &link_names,
152 const std::vector<double> &joint_angles,
153 std::vector<geometry_msgs::Pose> &poses)
const;
160 virtual bool initialize(
const std::string &robot_description,
161 const std::string &group_name,
162 const std::string &base_frame,
163 const std::string &tip_frame,
164 double search_discretization);
206 #endif // HAND_KINEMATICS_HAND_KINEMATICS_PLUGIN_H
const std::vector< std::string > & getLinkNames() const
Return all the link names in the order they are represented internally.
moveit_msgs::KinematicSolverInfo ik_solver_info_
std::string finger_base_name
const std::vector< std::string > & getJointNames() const
Return all the joint names in the order they are used internally.
ros::NodeHandle node_handle_
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, compute the joint angles to reach it.
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
Initialization function for the kinematics.
KDL::ChainIkSolverPos_NR_JL_coupling * ik_solver_pos
void generateRandomJntSeed(KDL::JntArray &jnt_pos_in) const
This method generates a random joint array vector between the joint limits so that local minima in IK...
moveit_msgs::KinematicSolverInfo solver_info_
double search_discretization_
KDL::ChainFkSolverPos_recursive * fk_solver
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Given a set of joint angles and a set of links, compute their pose.
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
moveit_msgs::KinematicSolverInfo fk_solver_info_
KDL::Chain_coupling kdl_chain_
bool isActive()
Specifies if the node is active or not.
KDL::ChainIkSolverVel_wdls_coupling * ik_solver_vel
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
ros::NodeHandle root_handle_