Public Member Functions | Private Member Functions | Private Attributes
Kinematics Class Reference

List of all members.

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
double epsilon
std::string finger_base_name
ros::ServiceServer fk_service
KDL::ChainFkSolverPos_recursivefk_solver
ros::ServiceServer fk_solver_info_service
ros::ServiceServer ik_service
ros::ServiceServer ik_solver_info_service
kinematics_msgs::KinematicSolverInfo info
unsigned int J5_idx_offset
KDL::JntArray joint_max
KDL::JntArray joint_min
std::vector< urdf::Vector3 > knuckle_axis
double length_middle
double length_proximal
std::vector< urdf::Poselink_offset
std::vector< std::string > link_offset_name
ros::NodeHandle nh
ros::NodeHandle nh_private
unsigned int num_joints
std::string root_name
tf::TransformListener tf_listener
std::string tip_name

Detailed Description

Definition at line 61 of file sr_kinematics.cpp.


Constructor & Destructor Documentation

Definition at line 131 of file sr_kinematics.cpp.


Member Function Documentation

This is the basic kinematics info service that will return information about the kinematics node.

Parameters:
requestmessage. See service definition for GetKinematicSolverInfo for more information on this message.
responsemessage. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 555 of file sr_kinematics.cpp.

This is the basic kinematics info service that will return information about the kinematics node.

Parameters:
requestmessage. See service definition for GetKinematicSolverInfo for more information on this message.
responsemessage. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 549 of file sr_kinematics.cpp.

int Kinematics::getJointIndex ( const std::string &  name) [private]

Definition at line 347 of file sr_kinematics.cpp.

int Kinematics::getKDLSegmentIndex ( const std::string &  name) [private]

Definition at line 355 of file sr_kinematics.cpp.

This is the basic forward kinematics service that will return information about the kinematics node.

Parameters:
requestmessage. See service definition for GetPositionFK for more information on this message.
responsemessage. See service definition for GetPositionFK for more information on this message.

Definition at line 561 of file sr_kinematics.cpp.

This is the basic IK service method that will compute and return an IK solution.

Parameters:
requestmessage. See service definition for GetPositionIK for more information on this message.
responsemessage. See service definition for GetPositionIK for more information on this message.

Definition at line 366 of file sr_kinematics.cpp.

bool Kinematics::init ( )

Definition at line 134 of file sr_kinematics.cpp.

bool Kinematics::loadModel ( const std::string  xml) [private]

Definition at line 207 of file sr_kinematics.cpp.

bool Kinematics::readJoints ( urdf::Model robot_model) [private]

Definition at line 232 of file sr_kinematics.cpp.


Member Data Documentation

Definition at line 70 of file sr_kinematics.cpp.

double Kinematics::epsilon [private]

Definition at line 79 of file sr_kinematics.cpp.

std::string Kinematics::finger_base_name [private]

Definition at line 68 of file sr_kinematics.cpp.

Definition at line 85 of file sr_kinematics.cpp.

Definition at line 77 of file sr_kinematics.cpp.

Definition at line 85 of file sr_kinematics.cpp.

Definition at line 84 of file sr_kinematics.cpp.

Definition at line 84 of file sr_kinematics.cpp.

Definition at line 89 of file sr_kinematics.cpp.

unsigned int Kinematics::J5_idx_offset [private]

Definition at line 82 of file sr_kinematics.cpp.

KDL::JntArray Kinematics::joint_max [private]

Definition at line 69 of file sr_kinematics.cpp.

KDL::JntArray Kinematics::joint_min [private]

Definition at line 69 of file sr_kinematics.cpp.

std::vector<urdf::Vector3> Kinematics::knuckle_axis [private]

Definition at line 74 of file sr_kinematics.cpp.

double Kinematics::length_middle [private]

Definition at line 80 of file sr_kinematics.cpp.

double Kinematics::length_proximal [private]

Definition at line 81 of file sr_kinematics.cpp.

std::vector<urdf::Pose> Kinematics::link_offset [private]

Definition at line 72 of file sr_kinematics.cpp.

std::vector<std::string> Kinematics::link_offset_name [private]

Definition at line 73 of file sr_kinematics.cpp.

Definition at line 67 of file sr_kinematics.cpp.

Definition at line 67 of file sr_kinematics.cpp.

unsigned int Kinematics::num_joints [private]

Definition at line 71 of file sr_kinematics.cpp.

std::string Kinematics::root_name [private]

Definition at line 68 of file sr_kinematics.cpp.

Definition at line 87 of file sr_kinematics.cpp.

std::string Kinematics::tip_name [private]

Definition at line 68 of file sr_kinematics.cpp.


The documentation for this class was generated from the following file:


sr_kinematics
Author(s): David LU, adapted for ShadowHand by Guillaume WALCK
autogenerated on Tue Jun 10 2014 15:13:32