
| 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. | |
| 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. | |
| 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) | 
| 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 114 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
Definition at line 133 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| void ikfast_kinematics_plugin::IKFastKinematicsPlugin::fillFreeParams | ( | int | count, | 
| int * | array | ||
| ) |  [private] | 
Definition at line 535 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| void ikfast_kinematics_plugin::IKFastKinematicsPlugin::getClosestSolution | ( | const IkSolutionList< IkReal > & | solutions, | 
| const std::vector< double > & | ik_seed_state, | ||
| std::vector< double > & | solution | ||
| ) | const  [private] | 
Definition at line 511 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::getCount | ( | int & | count, | 
| const int & | max_count, | ||
| const int & | min_count | ||
| ) | const  [private] | 
Definition at line 541 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| const std::vector<std::string>& ikfast_kinematics_plugin::IKFastKinematicsPlugin::getJointNames | ( | ) | const  [inline, private, virtual] | 
Implements kinematics::KinematicsBase.
Definition at line 125 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| const std::vector<std::string>& ikfast_kinematics_plugin::IKFastKinematicsPlugin::getLinkNames | ( | ) | const  [inline, private, virtual] | 
Implements kinematics::KinematicsBase.
Definition at line 126 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::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.
This FK routine is only used if 'use_plugin_fk' is set in the 'arm_kinematics_constraint_aware' node, otherwise ROS TF is used to calculate the forward kinematics
| 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 577 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::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 850 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| void ikfast_kinematics_plugin::IKFastKinematicsPlugin::getSolution | ( | const IkSolutionList< IkReal > & | solutions, | 
| int | i, | ||
| std::vector< double > & | solution | ||
| ) | const  [private] | 
Gets a specific solution from the set.
Definition at line 447 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| double ikfast_kinematics_plugin::IKFastKinematicsPlugin::harmonize | ( | const std::vector< double > & | ik_seed_state, | 
| std::vector< double > & | solution | ||
| ) | const  [private] | 
Definition at line 465 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::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 260 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::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 619 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::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 639 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::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 658 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::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 | 
Implements kinematics::KinematicsBase.
Definition at line 677 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| int ikfast_kinematics_plugin::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 374 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::active_  [private] | 
Definition at line 123 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| std::vector<int> ikfast_kinematics_plugin::IKFastKinematicsPlugin::free_params_  [private] | 
Definition at line 122 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| std::vector<bool> ikfast_kinematics_plugin::IKFastKinematicsPlugin::joint_has_limits_vector_  [private] | 
Definition at line 119 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| std::vector<double> ikfast_kinematics_plugin::IKFastKinematicsPlugin::joint_max_vector_  [private] | 
Definition at line 118 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| std::vector<double> ikfast_kinematics_plugin::IKFastKinematicsPlugin::joint_min_vector_  [private] | 
Definition at line 117 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| std::vector<std::string> ikfast_kinematics_plugin::IKFastKinematicsPlugin::joint_names_  [private] | 
Definition at line 116 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| std::vector<std::string> ikfast_kinematics_plugin::IKFastKinematicsPlugin::link_names_  [private] | 
Definition at line 120 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.
| size_t ikfast_kinematics_plugin::IKFastKinematicsPlugin::num_joints_  [private] | 
Definition at line 121 of file fanuc_m10ia_manipulator_ikfast_moveit_plugin.cpp.