#include <katana_openrave_kinematics.h>

Public Member Functions | |
| std::string | getBaseFrame () | 
| Return the frame in which the kinematics is operating.   | |
| std::vector< std::string > | getJointNames () | 
| Return all the joint names in the order they are used internally.   | |
| std::vector< std::string > | getLinkNames () | 
| 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.   | |
| std::string | getToolFrame () | 
| Return the links for which kinematics can be computed.   | |
| bool | initialize (std::string name) | 
| Initialization function for the kinematics.   | |
| bool | isActive () | 
| Specifies if the node is active or not.   | |
| KatanaKinematicsPlugin () | |
| 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).   | |
| 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).   | |
Protected Member Functions | |
| void | desiredPoseCallback (const std::vector< double > &joint_angles, const geometry_msgs::Pose &ik_pose, arm_navigation_msgs::ArmNavigationErrorCodes &error_code) | 
| void | jointSolutionCallback (const std::vector< double > &joint_angles, const geometry_msgs::Pose &ik_pose, arm_navigation_msgs::ArmNavigationErrorCodes &error_code) | 
Protected Attributes | |
| bool | active_ | 
| boost::function< void(const  geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)>  | desiredPoseCallback_ | 
| int | dimension_ | 
| ros::ServiceClient | fk_service_ | 
| kinematics_msgs::KinematicSolverInfo | fk_solver_info_ | 
| ros::ServiceClient | fk_solver_info_service_ | 
| ros::ServiceClient | ik_service_ | 
| kinematics_msgs::KinematicSolverInfo | ik_solver_info_ | 
| ros::ServiceClient | ik_solver_info_service_ | 
| ros::NodeHandle | node_handle_ | 
| urdf::Model | robot_model_ | 
| ros::NodeHandle | root_handle_ | 
| std::string | root_name_ | 
| boost::function< void(const  geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)>  | solutionCallback_ | 
| tf::TransformListener | tf_ | 
Definition at line 49 of file katana_openrave_kinematics.h.
Definition at line 41 of file katana_kinematics_plugin.cpp.
| void katana_kinematics_constraint_aware::KatanaKinematicsPlugin::desiredPoseCallback | ( | const std::vector< double > & | joint_angles, | 
| const geometry_msgs::Pose & | ik_pose, | ||
| arm_navigation_msgs::ArmNavigationErrorCodes & | error_code | ||
| ) |  [protected] | 
        
Definition at line 226 of file katana_kinematics_plugin.cpp.
| std::string katana_kinematics_constraint_aware::KatanaKinematicsPlugin::getBaseFrame | ( | ) |  [virtual] | 
        
Return the frame in which the kinematics is operating.
Implements kinematics::KinematicsBase.
Definition at line 424 of file katana_kinematics_plugin.cpp.
| std::vector< std::string > katana_kinematics_constraint_aware::KatanaKinematicsPlugin::getJointNames | ( | ) |  [virtual] | 
        
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 445 of file katana_kinematics_plugin.cpp.
| std::vector< std::string > katana_kinematics_constraint_aware::KatanaKinematicsPlugin::getLinkNames | ( | ) |  [virtual] | 
        
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 456 of file katana_kinematics_plugin.cpp.
| bool katana_kinematics_constraint_aware::KatanaKinematicsPlugin::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 367 of file katana_kinematics_plugin.cpp.
| bool katana_kinematics_constraint_aware::KatanaKinematicsPlugin::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 131 of file katana_kinematics_plugin.cpp.
| std::string katana_kinematics_constraint_aware::KatanaKinematicsPlugin::getToolFrame | ( | ) |  [virtual] | 
        
Return the links for which kinematics can be computed.
Implements kinematics::KinematicsBase.
Definition at line 434 of file katana_kinematics_plugin.cpp.
| bool katana_kinematics_constraint_aware::KatanaKinematicsPlugin::initialize | ( | std::string | name | ) |  [virtual] | 
        
Initialization function for the kinematics.
Implements kinematics::KinematicsBase.
Definition at line 53 of file katana_kinematics_plugin.cpp.
Specifies if the node is active or not.
Definition at line 46 of file katana_kinematics_plugin.cpp.
| void katana_kinematics_constraint_aware::KatanaKinematicsPlugin::jointSolutionCallback | ( | const std::vector< double > & | joint_angles, | 
| const geometry_msgs::Pose & | ik_pose, | ||
| arm_navigation_msgs::ArmNavigationErrorCodes & | error_code | ||
| ) |  [protected] | 
        
Definition at line 241 of file katana_kinematics_plugin.cpp.
| bool katana_kinematics_constraint_aware::KatanaKinematicsPlugin::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 178 of file katana_kinematics_plugin.cpp.
| bool katana_kinematics_constraint_aware::KatanaKinematicsPlugin::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 255 of file katana_kinematics_plugin.cpp.
Definition at line 138 of file katana_openrave_kinematics.h.
boost::function<void(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_solution, int &error_code)> katana_kinematics_constraint_aware::KatanaKinematicsPlugin::desiredPoseCallback_ [protected] | 
        
Definition at line 151 of file katana_openrave_kinematics.h.
Definition at line 146 of file katana_openrave_kinematics.h.
ros::ServiceClient katana_kinematics_constraint_aware::KatanaKinematicsPlugin::fk_service_ [protected] | 
        
Definition at line 143 of file katana_openrave_kinematics.h.
kinematics_msgs::KinematicSolverInfo katana_kinematics_constraint_aware::KatanaKinematicsPlugin::fk_solver_info_ [protected] | 
        
Definition at line 148 of file katana_openrave_kinematics.h.
ros::ServiceClient katana_kinematics_constraint_aware::KatanaKinematicsPlugin::fk_solver_info_service_ [protected] | 
        
Definition at line 143 of file katana_openrave_kinematics.h.
ros::ServiceClient katana_kinematics_constraint_aware::KatanaKinematicsPlugin::ik_service_ [protected] | 
        
Definition at line 143 of file katana_openrave_kinematics.h.
kinematics_msgs::KinematicSolverInfo katana_kinematics_constraint_aware::KatanaKinematicsPlugin::ik_solver_info_ [protected] | 
        
Definition at line 148 of file katana_openrave_kinematics.h.
ros::ServiceClient katana_kinematics_constraint_aware::KatanaKinematicsPlugin::ik_solver_info_service_ [protected] | 
        
Definition at line 143 of file katana_openrave_kinematics.h.
ros::NodeHandle katana_kinematics_constraint_aware::KatanaKinematicsPlugin::node_handle_ [protected] | 
        
Definition at line 141 of file katana_openrave_kinematics.h.
Definition at line 139 of file katana_openrave_kinematics.h.
ros::NodeHandle katana_kinematics_constraint_aware::KatanaKinematicsPlugin::root_handle_ [protected] | 
        
Definition at line 141 of file katana_openrave_kinematics.h.
std::string katana_kinematics_constraint_aware::KatanaKinematicsPlugin::root_name_ [protected] | 
        
Definition at line 145 of file katana_openrave_kinematics.h.
boost::function<void(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_solution, int &error_code)> katana_kinematics_constraint_aware::KatanaKinematicsPlugin::solutionCallback_ [protected] | 
        
Definition at line 153 of file katana_openrave_kinematics.h.
Definition at line 144 of file katana_openrave_kinematics.h.