Public Member Functions | |
| bool | init () | 
| Kinematics () | |
Private Member Functions | |
| bool | getFKSolverInfo (kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response) | 
| This is the basic kinematics info service that will return information about the kinematics node.   | |
| bool | getIKSolverInfo (kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response) | 
| This is the basic kinematics info service that will return information about the kinematics node.   | |
| int | getJointIndex (const std::string &name) | 
| int | getKDLSegmentIndex (const std::string &name) | 
| bool | getPositionFK (kinematics_msgs::GetPositionFK::Request &request, kinematics_msgs::GetPositionFK::Response &response) | 
| This is the basic forward kinematics service that will return information about the kinematics node.   | |
| bool | getPositionIK (kinematics_msgs::GetPositionIK::Request &request, kinematics_msgs::GetPositionIK::Response &response) | 
| This is the basic IK service method that will compute and return an IK solution.   | |
| bool | loadModel (const std::string xml) | 
| bool | readJoints (urdf::Model &robot_model) | 
Private Attributes | |
| KDL::Chain | chain | 
| ros::ServiceServer | fk_service | 
| KDL::ChainFkSolverPos_recursive * | fk_solver | 
| ros::ServiceServer | fk_solver_info_service | 
| ros::ServiceServer | ik_service | 
| ros::ServiceServer | ik_solver_info_service | 
| KDL::ChainIkSolverPos_NR_JL * | ik_solver_pos | 
| KDL::ChainIkSolverVel_pinv * | ik_solver_vel | 
| kinematics_msgs::KinematicSolverInfo | info | 
| KDL::JntArray | joint_max | 
| KDL::JntArray | joint_min | 
| ros::NodeHandle | nh | 
| ros::NodeHandle | nh_private | 
| unsigned int | num_joints | 
| std::string | root_name | 
| tf::TransformListener | tf_listener | 
| std::string | tip_name | 
Definition at line 23 of file arm_kinematics.cpp.
Definition at line 86 of file arm_kinematics.cpp.
| bool Kinematics::getFKSolverInfo | ( | kinematics_msgs::GetKinematicSolverInfo::Request & | request, | 
| kinematics_msgs::GetKinematicSolverInfo::Response & | response | ||
| ) |  [private] | 
        
This is the basic kinematics info service that will return information about the kinematics node.
| A | request message. See service definition for GetKinematicSolverInfo for more information on this message. | 
| The | response message. See service definition for GetKinematicSolverInfo for more information on this message. | 
Definition at line 301 of file arm_kinematics.cpp.
| bool Kinematics::getIKSolverInfo | ( | kinematics_msgs::GetKinematicSolverInfo::Request & | request, | 
| kinematics_msgs::GetKinematicSolverInfo::Response & | response | ||
| ) |  [private] | 
        
This is the basic kinematics info service that will return information about the kinematics node.
| A | request message. See service definition for GetKinematicSolverInfo for more information on this message. | 
| The | response message. See service definition for GetKinematicSolverInfo for more information on this message. | 
Definition at line 295 of file arm_kinematics.cpp.
| int Kinematics::getJointIndex | ( | const std::string & | name | ) |  [private] | 
        
Definition at line 225 of file arm_kinematics.cpp.
| int Kinematics::getKDLSegmentIndex | ( | const std::string & | name | ) |  [private] | 
        
Definition at line 233 of file arm_kinematics.cpp.
| bool Kinematics::getPositionFK | ( | kinematics_msgs::GetPositionFK::Request & | request, | 
| kinematics_msgs::GetPositionFK::Response & | response | ||
| ) |  [private] | 
        
This is the basic forward kinematics service that will return information about the kinematics node.
| A | request message. See service definition for GetPositionFK for more information on this message. | 
| The | response message. See service definition for GetPositionFK for more information on this message. | 
Definition at line 307 of file arm_kinematics.cpp.
| bool Kinematics::getPositionIK | ( | kinematics_msgs::GetPositionIK::Request & | request, | 
| kinematics_msgs::GetPositionIK::Response & | response | ||
| ) |  [private] | 
        
This is the basic IK service method that will compute and return an IK solution.
| A | request message. See service definition for GetPositionIK for more information on this message. | 
| The | response message. See service definition for GetPositionIK for more information on this message. | 
Definition at line 244 of file arm_kinematics.cpp.
| bool Kinematics::init | ( | ) | 
Definition at line 89 of file arm_kinematics.cpp.
| bool Kinematics::loadModel | ( | const std::string | xml | ) |  [private] | 
        
Definition at line 139 of file arm_kinematics.cpp.
| bool Kinematics::readJoints | ( | urdf::Model & | robot_model | ) |  [private] | 
        
Definition at line 164 of file arm_kinematics.cpp.
KDL::Chain Kinematics::chain [private] | 
        
Definition at line 32 of file arm_kinematics.cpp.
ros::ServiceServer Kinematics::fk_service [private] | 
        
Definition at line 40 of file arm_kinematics.cpp.
Definition at line 35 of file arm_kinematics.cpp.
Definition at line 40 of file arm_kinematics.cpp.
ros::ServiceServer Kinematics::ik_service [private] | 
        
Definition at line 39 of file arm_kinematics.cpp.
Definition at line 39 of file arm_kinematics.cpp.
Definition at line 36 of file arm_kinematics.cpp.
Definition at line 37 of file arm_kinematics.cpp.
kinematics_msgs::KinematicSolverInfo Kinematics::info [private] | 
        
Definition at line 44 of file arm_kinematics.cpp.
KDL::JntArray Kinematics::joint_max [private] | 
        
Definition at line 31 of file arm_kinematics.cpp.
KDL::JntArray Kinematics::joint_min [private] | 
        
Definition at line 31 of file arm_kinematics.cpp.
ros::NodeHandle Kinematics::nh [private] | 
        
Definition at line 29 of file arm_kinematics.cpp.
ros::NodeHandle Kinematics::nh_private [private] | 
        
Definition at line 29 of file arm_kinematics.cpp.
unsigned int Kinematics::num_joints [private] | 
        
Definition at line 33 of file arm_kinematics.cpp.
std::string Kinematics::root_name [private] | 
        
Definition at line 30 of file arm_kinematics.cpp.
tf::TransformListener Kinematics::tf_listener [private] | 
        
Definition at line 42 of file arm_kinematics.cpp.
std::string Kinematics::tip_name [private] | 
        
Definition at line 30 of file arm_kinematics.cpp.