
| Public Member Functions | |
| 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. | |
| 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. | |
| bool | getPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, kinematics::KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const | 
| Given a desired pose of the end-effector, compute the set joint angles solutions that are able to reach it. | |
| IKFastKinematicsPlugin () | |
| 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). | |
| 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). | |
| 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). | |
| 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. | |
| bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) | 
| Overrides the default method to prevent changing the redundant joints. | |
| void | setSearchDiscretization (const std::map< int, double > &discretization) | 
| Sets the discretization value for the redundant joint. | |
| Private Member Functions | |
| void | fillFreeParams (int count, int *array) | 
| 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 | 
| const std::vector< std::string > & | getJointNames () 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. | |
| 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 | sampleRedundantJoint (kinematics::DiscretizationMethod method, std::vector< double > &sampled_joint_vals) const | 
| samples the designated redundant joint using the chosen discretization method | |
| int | solve (KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const | 
| Calls the IK solver from IKFast. | |
| Private Attributes | |
| bool | active_ | 
| std::vector< int > | free_params_ | 
| std::vector< bool > | joint_has_limits_vector_ | 
| std::vector< double > | joint_max_vector_ | 
| std::vector< double > | joint_min_vector_ | 
| std::vector< std::string > | joint_names_ | 
| std::vector< std::string > | link_names_ | 
| size_t | num_joints_ | 
Definition at line 142 of file katana_450_6m90a_ikfast_plugin.cpp.
Definition at line 166 of file katana_450_6m90a_ikfast_plugin.cpp.
| void katana_450_6m90a_kinematics::IKFastKinematicsPlugin::fillFreeParams | ( | int | count, | 
| int * | array | ||
| ) |  [private] | 
Definition at line 657 of file katana_450_6m90a_ikfast_plugin.cpp.
| void katana_450_6m90a_kinematics::IKFastKinematicsPlugin::getClosestSolution | ( | const IkSolutionList< IkReal > & | solutions, | 
| const std::vector< double > & | ik_seed_state, | ||
| std::vector< double > & | solution | ||
| ) | const  [private] | 
Definition at line 629 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::getCount | ( | int & | count, | 
| const int & | max_count, | ||
| const int & | min_count | ||
| ) | const  [private] | 
Definition at line 664 of file katana_450_6m90a_ikfast_plugin.cpp.
| const std::vector<std::string>& katana_450_6m90a_kinematics::IKFastKinematicsPlugin::getJointNames | ( | ) | const  [inline, private, virtual] | 
Implements kinematics::KinematicsBase.
Definition at line 153 of file katana_450_6m90a_ikfast_plugin.cpp.
| const std::vector<std::string>& katana_450_6m90a_kinematics::IKFastKinematicsPlugin::getLinkNames | ( | ) | const  [inline, private, virtual] | 
Implements kinematics::KinematicsBase.
Definition at line 157 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::getPositionFK | ( | const std::vector< std::string > & | link_names, | 
| const std::vector< double > & | joint_angles, | ||
| std::vector< geometry_msgs::Pose > & | poses | ||
| ) | const  [virtual] | 
Given a set of joint angles and a set of links, compute their pose.
| link_names | A set of links for which FK needs to be computed | 
| joint_angles | The state for which FK is being computed | 
| poses | The resultant set of poses (in the frame returned by getBaseFrame()) | 
Implements kinematics::KinematicsBase.
Definition at line 700 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::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  [virtual] | 
Given a desired pose of the end-effector, compute the joint angles to reach it.
| ik_pose | the desired pose of the link | 
| ik_seed_state | an initial guess solution for the inverse kinematics | 
| solution | the solution vector | 
| error_code | an error code that encodes the reason for failure or success | 
Implements kinematics::KinematicsBase.
Definition at line 997 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::getPositionIK | ( | const std::vector< geometry_msgs::Pose > & | ik_poses, | 
| const std::vector< double > & | ik_seed_state, | ||
| std::vector< std::vector< double > > & | solutions, | ||
| kinematics::KinematicsResult & | result, | ||
| const kinematics::KinematicsQueryOptions & | options | ||
| ) | const  [virtual] | 
Given a desired pose of the end-effector, compute the set joint angles solutions that are able to reach it.
This is a default implementation that returns only one solution and so its result is equivalent to calling 'getPositionIK(...)' with a zero initialized seed.
| ik_poses | The desired pose of each tip link | 
| ik_seed_state | an initial guess solution for the inverse kinematics | 
| solutions | A vector of vectors where each entry is a valid joint solution | 
| result | A struct that reports the results of the query | 
| options | An option struct which contains the type of redundancy discretization used. This default implementation only supports the KinmaticSearches::NO_DISCRETIZATION method; requesting any other will result in failure. | 
Reimplemented from kinematics::KinematicsBase.
Definition at line 1067 of file katana_450_6m90a_ikfast_plugin.cpp.
| void katana_450_6m90a_kinematics::IKFastKinematicsPlugin::getSolution | ( | const IkSolutionList< IkReal > & | solutions, | 
| int | i, | ||
| std::vector< double > & | solution | ||
| ) | const  [private] | 
Gets a specific solution from the set.
Definition at line 560 of file katana_450_6m90a_ikfast_plugin.cpp.
| double katana_450_6m90a_kinematics::IKFastKinematicsPlugin::harmonize | ( | const std::vector< double > & | ik_seed_state, | 
| std::vector< double > & | solution | ||
| ) | const  [private] | 
Definition at line 579 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::initialize | ( | const std::string & | robot_description, | 
| const std::string & | group_name, | ||
| const std::string & | base_name, | ||
| const std::string & | tip_name, | ||
| double | search_discretization | ||
| ) |  [private, virtual] | 
Implements kinematics::KinematicsBase.
Definition at line 320 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::sampleRedundantJoint | ( | kinematics::DiscretizationMethod | method, | 
| std::vector< double > & | sampled_joint_vals | ||
| ) | const  [private] | 
samples the designated redundant joint using the chosen discretization method
| method | An enumeration flag indicating the discretization method to be used | 
| sampled_joint_vals | Sampled joint values for the redundant joint | 
Definition at line 1210 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::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  [virtual] | 
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).
| ik_pose | the desired pose of the link | 
| ik_seed_state | an initial guess solution for the inverse kinematics | 
Implements kinematics::KinematicsBase.
Definition at line 749 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::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  [virtual] | 
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).
| ik_pose | the desired pose of the link | 
| ik_seed_state | an initial guess solution for the inverse kinematics | 
| the | distance that the redundancy can be from the current position | 
Implements kinematics::KinematicsBase.
Definition at line 761 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::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  [virtual] | 
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).
| ik_pose | the desired pose of the link | 
| ik_seed_state | an initial guess solution for the inverse kinematics | 
Implements kinematics::KinematicsBase.
Definition at line 772 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::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  [virtual] | 
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.
| ik_pose | the desired pose of the link | 
| ik_seed_state | an initial guess solution for the inverse kinematics | 
| consistency_limit | the distance that the redundancy can be from the current position | 
search_mode is currently fixed during code generation
Implements kinematics::KinematicsBase.
Definition at line 783 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::setRedundantJoints | ( | const std::vector< unsigned int > & | redundant_joint_indices | ) |  [virtual] | 
Overrides the default method to prevent changing the redundant joints.
Reimplemented from kinematics::KinematicsBase.
Definition at line 476 of file katana_450_6m90a_ikfast_plugin.cpp.
| void katana_450_6m90a_kinematics::IKFastKinematicsPlugin::setSearchDiscretization | ( | const std::map< int, double > & | discretization | ) | 
Sets the discretization value for the redundant joint.
Since this ikfast implementation allows for one redundant joint then only the first entry will be in the discretization map will be used. Calling this method replaces previous discretization settings.
| discretization | a map of joint indices and discretization value pairs. | 
Reimplemented from kinematics::KinematicsBase.
Definition at line 443 of file katana_450_6m90a_ikfast_plugin.cpp.
| int katana_450_6m90a_kinematics::IKFastKinematicsPlugin::solve | ( | KDL::Frame & | pose_frame, | 
| const std::vector< double > & | vfree, | ||
| IkSolutionList< IkReal > & | solutions | ||
| ) | const  [private] | 
Calls the IK solver from IKFast.
Definition at line 482 of file katana_450_6m90a_ikfast_plugin.cpp.
| bool katana_450_6m90a_kinematics::IKFastKinematicsPlugin::active_  [private] | 
Definition at line 151 of file katana_450_6m90a_ikfast_plugin.cpp.
| std::vector<int> katana_450_6m90a_kinematics::IKFastKinematicsPlugin::free_params_  [private] | 
Definition at line 150 of file katana_450_6m90a_ikfast_plugin.cpp.
| std::vector<bool> katana_450_6m90a_kinematics::IKFastKinematicsPlugin::joint_has_limits_vector_  [private] | 
Definition at line 147 of file katana_450_6m90a_ikfast_plugin.cpp.
| std::vector<double> katana_450_6m90a_kinematics::IKFastKinematicsPlugin::joint_max_vector_  [private] | 
Definition at line 146 of file katana_450_6m90a_ikfast_plugin.cpp.
| std::vector<double> katana_450_6m90a_kinematics::IKFastKinematicsPlugin::joint_min_vector_  [private] | 
Definition at line 145 of file katana_450_6m90a_ikfast_plugin.cpp.
| std::vector<std::string> katana_450_6m90a_kinematics::IKFastKinematicsPlugin::joint_names_  [private] | 
Definition at line 144 of file katana_450_6m90a_ikfast_plugin.cpp.
| std::vector<std::string> katana_450_6m90a_kinematics::IKFastKinematicsPlugin::link_names_  [private] | 
Definition at line 148 of file katana_450_6m90a_ikfast_plugin.cpp.
| size_t katana_450_6m90a_kinematics::IKFastKinematicsPlugin::num_joints_  [private] | 
Definition at line 149 of file katana_450_6m90a_ikfast_plugin.cpp.