#include <kdl_arm_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. | |
| bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) |
| 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, int &error_code) |
| Given a desired pose of the end-effector, compute the joint angles to reach it. | |
| bool | initialize (const std::string &group_name, const std::string &base_name, const std::string &tip_name, const double &search_discretization=.01) |
| Initialization function for the kinematics. | |
| bool | isActive () |
| Specifies if the node is active or not. | |
| KDLArmKinematicsPlugin () | |
| bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, const double &timeout, std::vector< double > &solution, int &error_code) |
| 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 | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, const double &timeout, const unsigned int &redundancy, const double &consistency_limit, std::vector< double > &solution, int &error_code) |
| 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, const double &timeout, std::vector< double > &solution, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &desired_pose_callback, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &solution_callback, int &error_code) |
| 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 | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, const double &timeout, const unsigned int &redundancy, const double &consistency_limit, std::vector< double > &solution, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &desired_pose_callback, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &solution_callback, int &error_code) |
| 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. | |
Protected Member Functions | |
| bool | checkConsistency (const KDL::JntArray &seed_state, const unsigned int &redundancy, const double &consistency_limit, const KDL::JntArray &solution) const |
| double | genRandomNumber (const double &min, const double &max) |
| int | getJointIndex (const std::string &name) |
| int | getKDLSegmentIndex (const std::string &name) |
| KDL::JntArray | getRandomConfiguration () |
| KDL::JntArray | getRandomConfiguration (const KDL::JntArray &seed_state, const unsigned int &redundancy, const double &consistency_limit) |
| bool | loadModel (const std::string xml) |
| bool | readJoints (urdf::Model &robot_model) |
Protected Attributes | |
| bool | active_ |
| kinematics_msgs::KinematicSolverInfo | chain_info_ |
| unsigned int | dimension_ |
| boost::shared_ptr < KDL::ChainFkSolverPos_recursive > | fk_solver_ |
| boost::shared_ptr < KDL::ChainIkSolverPos_NR_JL > | ik_solver_pos_ |
| boost::shared_ptr < KDL::ChainIkSolverVel_pinv > | ik_solver_vel_ |
| KDL::JntArray | joint_max_ |
| KDL::JntArray | joint_min_ |
| KDL::Chain | kdl_chain_ |
| int | max_search_iterations_ |
Definition at line 76 of file kdl_arm_kinematics_plugin.h.
Definition at line 50 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::checkConsistency | ( | const KDL::JntArray & | seed_state, |
| const unsigned int & | redundancy, | ||
| const double & | consistency_limit, | ||
| const KDL::JntArray & | solution | ||
| ) | const [protected] |
Definition at line 96 of file kdl_arm_kinematics_plugin.cpp.
| double arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::genRandomNumber | ( | const double & | min, |
| const double & | max | ||
| ) | [protected] |
Definition at line 62 of file kdl_arm_kinematics_plugin.cpp.
| int arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getJointIndex | ( | const std::string & | name | ) | [protected] |
Definition at line 244 of file kdl_arm_kinematics_plugin.cpp.
| const std::vector< std::string > & arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getJointNames | ( | ) | const [virtual] |
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 616 of file kdl_arm_kinematics_plugin.cpp.
| int arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getKDLSegmentIndex | ( | const std::string & | name | ) | [protected] |
Definition at line 253 of file kdl_arm_kinematics_plugin.cpp.
| const std::vector< std::string > & arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getLinkNames | ( | ) | const [virtual] |
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 625 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getPositionFK | ( | const std::vector< std::string > & | link_names, |
| const std::vector< double > & | joint_angles, | ||
| std::vector< geometry_msgs::Pose > & | poses | ||
| ) | [virtual] |
Given a set of joint angles and a set of links, compute their pose.
| request | - the request contains the joint angles, set of links for which poses are to be computed and a timeout |
| response | - the response contains stamped pose information for all the requested links |
Implements kinematics::KinematicsBase.
Definition at line 576 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getPositionIK | ( | const geometry_msgs::Pose & | ik_pose, |
| const std::vector< double > & | ik_seed_state, | ||
| std::vector< double > & | solution, | ||
| int & | error_code | ||
| ) | [virtual] |
Given a desired pose of the end-effector, compute the joint angles to reach it.
| ik_link_name | - the name of the link for which IK is being computed |
| 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 265 of file kdl_arm_kinematics_plugin.cpp.
| KDL::JntArray arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getRandomConfiguration | ( | ) | [protected] |
Definition at line 69 of file kdl_arm_kinematics_plugin.cpp.
| KDL::JntArray arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getRandomConfiguration | ( | const KDL::JntArray & | seed_state, |
| const unsigned int & | redundancy, | ||
| const double & | consistency_limit | ||
| ) | [protected] |
Definition at line 78 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::initialize | ( | const std::string & | group_name, |
| const std::string & | base_name, | ||
| const std::string & | tip_name, | ||
| const double & | search_discretization = .01 |
||
| ) | [virtual] |
Initialization function for the kinematics.
Implements kinematics::KinematicsBase.
Definition at line 115 of file kdl_arm_kinematics_plugin.cpp.
Specifies if the node is active or not.
Definition at line 55 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::loadModel | ( | const std::string | xml | ) | [protected] |
Definition at line 156 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::readJoints | ( | urdf::Model & | robot_model | ) | [protected] |
Definition at line 180 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::searchPositionIK | ( | const geometry_msgs::Pose & | ik_pose, |
| const std::vector< double > & | ik_seed_state, | ||
| const double & | timeout, | ||
| std::vector< double > & | solution, | ||
| int & | error_code | ||
| ) | [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 316 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::searchPositionIK | ( | const geometry_msgs::Pose & | ik_pose, |
| const std::vector< double > & | ik_seed_state, | ||
| const double & | timeout, | ||
| const unsigned int & | redundancy, | ||
| const double & | consistency_limit, | ||
| std::vector< double > & | solution, | ||
| int & | error_code | ||
| ) | [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 373 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::searchPositionIK | ( | const geometry_msgs::Pose & | ik_pose, |
| const std::vector< double > & | ik_seed_state, | ||
| const double & | timeout, | ||
| std::vector< double > & | solution, | ||
| const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> & | desired_pose_callback, | ||
| const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> & | solution_callback, | ||
| int & | error_code | ||
| ) | [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 434 of file kdl_arm_kinematics_plugin.cpp.
| bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::searchPositionIK | ( | const geometry_msgs::Pose & | ik_pose, |
| const std::vector< double > & | ik_seed_state, | ||
| const double & | timeout, | ||
| const unsigned int & | redundancy, | ||
| const double & | consistency_limit, | ||
| std::vector< double > & | solution, | ||
| const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> & | desired_pose_callback, | ||
| const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> & | solution_callback, | ||
| int & | error_code | ||
| ) | [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 502 of file kdl_arm_kinematics_plugin.cpp.
bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::active_ [protected] |
Definition at line 217 of file kdl_arm_kinematics_plugin.h.
kinematics_msgs::KinematicSolverInfo arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::chain_info_ [protected] |
Definition at line 218 of file kdl_arm_kinematics_plugin.h.
unsigned int arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::dimension_ [protected] |
Definition at line 224 of file kdl_arm_kinematics_plugin.h.
boost::shared_ptr<KDL::ChainFkSolverPos_recursive> arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::fk_solver_ [protected] |
Definition at line 221 of file kdl_arm_kinematics_plugin.h.
boost::shared_ptr<KDL::ChainIkSolverPos_NR_JL> arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::ik_solver_pos_ [protected] |
Definition at line 222 of file kdl_arm_kinematics_plugin.h.
boost::shared_ptr<KDL::ChainIkSolverVel_pinv> arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::ik_solver_vel_ [protected] |
Definition at line 220 of file kdl_arm_kinematics_plugin.h.
KDL::JntArray arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::joint_max_ [protected] |
Definition at line 226 of file kdl_arm_kinematics_plugin.h.
KDL::JntArray arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::joint_min_ [protected] |
Definition at line 226 of file kdl_arm_kinematics_plugin.h.
Definition at line 225 of file kdl_arm_kinematics_plugin.h.
Definition at line 215 of file kdl_arm_kinematics_plugin.h.