|  | 
| 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.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
|  | IKFastKinematicsPlugin () | 
|  | 
|  | IKFastKinematicsPlugin () | 
|  | 
| bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines). The consistency_limit specifies that only certain redundancy positions around those specified in the seed state are admissible and need to be searched.  More... 
 | 
|  | 
| bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines). The consistency_limit specifies that only certain redundancy positions around those specified in the seed state are admissible and need to be searched.  More... 
 | 
|  | 
| bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).  More... 
 | 
|  | 
| bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).  More... 
 | 
|  | 
| bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).  More... 
 | 
|  | 
| bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).  More... 
 | 
|  | 
| 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 | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).  More... 
 | 
|  | 
| 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 | 
|  | Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).  More... 
 | 
|  | 
| virtual const std::string & | getBaseFrame () const | 
|  | 
| double | getDefaultTimeout () const | 
|  | 
| virtual const std::string & | getGroupName () const | 
|  | 
| virtual bool | getPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const | 
|  | 
| virtual void | getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const | 
|  | 
| double | getSearchDiscretization (int joint_index=0) const | 
|  | 
| std::vector< DiscretizationMethod > | getSupportedDiscretizationMethods () const | 
|  | 
| virtual const std::string & | getTipFrame () const | 
|  | 
| virtual const std::vector< std::string > & | getTipFrames () const | 
|  | 
| virtual bool | initialize (const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) | 
|  | 
| virtual bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) | 
|  | 
|  | KinematicsBase () | 
|  | 
| virtual bool | searchPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const | 
|  | 
| void | setDefaultTimeout (double timeout) | 
|  | 
| bool | setRedundantJoints (const std::vector< std::string > &redundant_joint_names) | 
|  | 
| virtual bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) | 
|  | 
| void | setSearchDiscretization (const std::map< int, double > &discretization) | 
|  | 
| void | setSearchDiscretization (double sd) | 
|  | 
| virtual void | setValues (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization) | 
|  | 
| virtual void | setValues (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) | 
|  | 
| virtual bool | supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const | 
|  | 
| virtual | ~KinematicsBase () | 
|  | 
|  | 
| void | fillFreeParams (int count, int *array) | 
|  | 
| void | fillFreeParams (int count, int *array) | 
|  | 
| void | getClosestSolution (const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const | 
|  | 
| void | getClosestSolution (const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const | 
|  | 
| bool | getCount (int &count, const int &max_count, const int &min_count) const | 
|  | 
| bool | getCount (int &count, const int &max_count, const int &min_count) const | 
|  | 
| const std::vector< std::string > & | getJointNames () const | 
|  | 
| const std::vector< std::string > & | getJointNames () const | 
|  | 
| const std::vector< std::string > & | getLinkNames () const | 
|  | 
| const std::vector< std::string > & | getLinkNames () const | 
|  | 
| void | getSolution (const IkSolutionList< IkReal > &solutions, int i, std::vector< double > &solution) const | 
|  | Gets a specific solution from the set.  More... 
 | 
|  | 
| void | getSolution (const IkSolutionList< IkReal > &solutions, int i, std::vector< double > &solution) const | 
|  | Gets a specific solution from the set.  More... 
 | 
|  | 
| double | harmonize (const std::vector< double > &ik_seed_state, std::vector< double > &solution) const | 
|  | 
| double | harmonize (const std::vector< double > &ik_seed_state, std::vector< double > &solution) const | 
|  | 
| bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization) | 
|  | 
| bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization) | 
|  | 
| int | solve (KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const | 
|  | Calls the IK solver from IKFast.  More... 
 | 
|  | 
| int | solve (KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const | 
|  | Calls the IK solver from IKFast.  More... 
 | 
|  |