Specific implementation of kinematics using KDL. This version can be used with any robot. More...
#include <kdl_kinematics_plugin.h>

| Public Member Functions | |
| const std::vector< std::string > & | getJointNames () const | 
| Return all the joint names in the order they are used internally. | |
| const std::vector< std::string > & | getLinkNames () const | 
| Return all the link names in the order they are represented internally. | |
| virtual bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const | 
| 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 | 
| virtual 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) | 
| KDLKinematicsPlugin () | |
| Default constructor. | |
| 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 | 
| virtual 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 | 
| virtual 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 | 
| virtual 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 | 
| Protected Member Functions | |
| 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 std::vector< double > &consistency_limits, 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). | |
| virtual bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) | 
| Private Member Functions | |
| bool | checkConsistency (const KDL::JntArray &seed_state, const std::vector< double > &consistency_limit, const KDL::JntArray &solution) const | 
| Check whether the solution lies within the consistency limit of the seed state. | |
| int | getJointIndex (const std::string &name) const | 
| int | getKDLSegmentIndex (const std::string &name) const | 
| void | getRandomConfiguration (KDL::JntArray &jnt_array, bool lock_redundancy) const | 
| void | getRandomConfiguration (const KDL::JntArray &seed_state, const std::vector< double > &consistency_limits, KDL::JntArray &jnt_array, bool lock_redundancy) const | 
| Get a random configuration within joint limits close to the seed state. | |
| bool | isRedundantJoint (unsigned int index) const | 
| bool | timedOut (const ros::WallTime &start_time, double duration) const | 
| Private Attributes | |
| bool | active_ | 
| unsigned int | dimension_ | 
| double | epsilon_ | 
| moveit_msgs::KinematicSolverInfo | fk_chain_info_ | 
| moveit_msgs::KinematicSolverInfo | ik_chain_info_ | 
| KDL::JntArray | joint_max_ | 
| KDL::JntArray | joint_min_ | 
| robot_model::JointModelGroup * | joint_model_group_ | 
| KDL::Chain | kdl_chain_ | 
| double | max_solver_iterations_ | 
| std::vector< JointMimic > | mimic_joints_ | 
| int | num_possible_redundant_joints_ | 
| bool | position_ik_ | 
| random_numbers::RandomNumberGenerator | random_number_generator_ | 
| std::vector< unsigned int > | redundant_joints_map_index_ | 
| robot_model::RobotModelPtr | robot_model_ | 
| robot_state::RobotStatePtr | state_ | 
| robot_state::RobotStatePtr | state_2_ | 
Specific implementation of kinematics using KDL. This version can be used with any robot.
Definition at line 73 of file kdl_kinematics_plugin.h.
Default constructor.
Definition at line 55 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::checkConsistency | ( | const KDL::JntArray & | seed_state, | 
| const std::vector< double > & | consistency_limit, | ||
| const KDL::JntArray & | solution | ||
| ) | const  [private] | 
Check whether the solution lies within the consistency limit of the seed state.
| seed_state | Seed state | 
| redundancy | Index of the redundant joint within the chain | 
| consistency_limit | The returned state for redundant joint should be in the range [seed_state(redundancy_limit)-consistency_limit,seed_state(redundancy_limit)+consistency_limit] | 
| solution | solution configuration | 
Definition at line 118 of file kdl_kinematics_plugin.cpp.
| int kdl_kinematics_plugin::KDLKinematicsPlugin::getJointIndex | ( | const std::string & | name | ) | const  [private] | 
Definition at line 349 of file kdl_kinematics_plugin.cpp.
| const std::vector< std::string > & kdl_kinematics_plugin::KDLKinematicsPlugin::getJointNames | ( | ) | const  [virtual] | 
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 605 of file kdl_kinematics_plugin.cpp.
| int kdl_kinematics_plugin::KDLKinematicsPlugin::getKDLSegmentIndex | ( | const std::string & | name | ) | const  [private] | 
Definition at line 359 of file kdl_kinematics_plugin.cpp.
| const std::vector< std::string > & kdl_kinematics_plugin::KDLKinematicsPlugin::getLinkNames | ( | ) | const  [virtual] | 
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 610 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::getPositionFK | ( | const std::vector< std::string > & | link_names, | 
| const std::vector< double > & | joint_angles, | ||
| std::vector< geometry_msgs::Pose > & | poses | ||
| ) | const  [virtual] | 
Implements kinematics::KinematicsBase.
Definition at line 559 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::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] | 
Implements kinematics::KinematicsBase.
Definition at line 378 of file kdl_kinematics_plugin.cpp.
| void kdl_kinematics_plugin::KDLKinematicsPlugin::getRandomConfiguration | ( | KDL::JntArray & | jnt_array, | 
| bool | lock_redundancy | ||
| ) | const  [private] | 
Definition at line 59 of file kdl_kinematics_plugin.cpp.
| void kdl_kinematics_plugin::KDLKinematicsPlugin::getRandomConfiguration | ( | const KDL::JntArray & | seed_state, | 
| const std::vector< double > & | consistency_limits, | ||
| KDL::JntArray & | jnt_array, | ||
| bool | lock_redundancy | ||
| ) | const  [private] | 
Get a random configuration within joint limits close to the seed state.
| seed_state | Seed state | 
| redundancy | Index of the redundant joint within the chain | 
| consistency_limit | The returned state will contain a value for the redundant joint in the range [seed_state(redundancy_limit)-consistency_limit,seed_state(redundancy_limit)+consistency_limit] | 
| jnt_array | Returned random configuration | 
Definition at line 81 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::initialize | ( | const std::string & | robot_description, | 
| const std::string & | group_name, | ||
| const std::string & | base_name, | ||
| const std::string & | tip_name, | ||
| double | search_discretization | ||
| ) |  [virtual] | 
Implements kinematics::KinematicsBase.
Definition at line 128 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::isRedundantJoint | ( | unsigned int | index | ) | const  [private] | 
Definition at line 73 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::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] | 
Implements kinematics::KinematicsBase.
Definition at line 389 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::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] | 
Implements kinematics::KinematicsBase.
Definition at line 401 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::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] | 
Implements kinematics::KinematicsBase.
Definition at line 411 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::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] | 
Implements kinematics::KinematicsBase.
Definition at line 422 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::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 std::vector< double > & | consistency_limits, | ||
| const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() | ||
| ) | const  [protected] | 
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 | 
| timeout | The amount of time (in seconds) available to the solver | 
| solution | the solution vector | 
| solution_callback | A callback solution for the IK solution | 
| error_code | an error code that encodes the reason for failure or success | 
| check_consistency | Set to true if consistency check needs to be performed | 
| redundancy | The index of the redundant joint | 
| consistency_limit | The returned solutuion will contain a value for the redundant joint in the range [seed_state(redundancy_limit)-consistency_limit,seed_state(redundancy_limit)+consistency_limit] | 
Definition at line 432 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::setRedundantJoints | ( | const std::vector< unsigned int > & | redundant_joint_indices | ) |  [protected, virtual] | 
Reimplemented from kinematics::KinematicsBase.
Definition at line 291 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::timedOut | ( | const ros::WallTime & | start_time, | 
| double | duration | ||
| ) | const  [private] | 
Definition at line 373 of file kdl_kinematics_plugin.cpp.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::active_  [private] | 
Definition at line 180 of file kdl_kinematics_plugin.h.
| unsigned int kdl_kinematics_plugin::KDLKinematicsPlugin::dimension_  [private] | 
Definition at line 188 of file kdl_kinematics_plugin.h.
| double kdl_kinematics_plugin::KDLKinematicsPlugin::epsilon_  [private] | 
Definition at line 205 of file kdl_kinematics_plugin.h.
| moveit_msgs::KinematicSolverInfo kdl_kinematics_plugin::KDLKinematicsPlugin::fk_chain_info_  [private] | 
Stores information for the inverse kinematics solver
Definition at line 184 of file kdl_kinematics_plugin.h.
| moveit_msgs::KinematicSolverInfo kdl_kinematics_plugin::KDLKinematicsPlugin::ik_chain_info_  [private] | 
Internal variable that indicates whether solvers are configured and ready
Definition at line 182 of file kdl_kinematics_plugin.h.
Definition at line 190 of file kdl_kinematics_plugin.h.
Dimension of the group
Definition at line 190 of file kdl_kinematics_plugin.h.
| robot_model::JointModelGroup* kdl_kinematics_plugin::KDLKinematicsPlugin::joint_model_group_  [private] | 
Definition at line 203 of file kdl_kinematics_plugin.h.
Store information for the forward kinematics solver
Definition at line 186 of file kdl_kinematics_plugin.h.
| double kdl_kinematics_plugin::KDLKinematicsPlugin::max_solver_iterations_  [private] | 
Definition at line 204 of file kdl_kinematics_plugin.h.
| std::vector<JointMimic> kdl_kinematics_plugin::KDLKinematicsPlugin::mimic_joints_  [private] | 
Definition at line 206 of file kdl_kinematics_plugin.h.
Definition at line 198 of file kdl_kinematics_plugin.h.
| bool kdl_kinematics_plugin::KDLKinematicsPlugin::position_ik_  [private] | 
Definition at line 202 of file kdl_kinematics_plugin.h.
| random_numbers::RandomNumberGenerator kdl_kinematics_plugin::KDLKinematicsPlugin::random_number_generator_  [mutable, private] | 
Joint limits
Definition at line 192 of file kdl_kinematics_plugin.h.
| std::vector<unsigned int> kdl_kinematics_plugin::KDLKinematicsPlugin::redundant_joints_map_index_  [private] | 
Definition at line 199 of file kdl_kinematics_plugin.h.
| robot_model::RobotModelPtr kdl_kinematics_plugin::KDLKinematicsPlugin::robot_model_  [private] | 
Definition at line 194 of file kdl_kinematics_plugin.h.
| robot_state::RobotStatePtr kdl_kinematics_plugin::KDLKinematicsPlugin::state_  [private] | 
Definition at line 196 of file kdl_kinematics_plugin.h.
| robot_state::RobotStatePtr kdl_kinematics_plugin::KDLKinematicsPlugin::state_2_  [private] | 
Definition at line 196 of file kdl_kinematics_plugin.h.