Definition at line 61 of file sr_kinematics.cpp.
Definition at line 131 of file sr_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.
request | message. See service definition for GetKinematicSolverInfo for more information on this message. |
response | message. See service definition for GetKinematicSolverInfo for more information on this message. |
Definition at line 555 of file sr_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.
request | message. See service definition for GetKinematicSolverInfo for more information on this message. |
response | message. 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.
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.
request | message. See service definition for GetPositionFK for more information on this message. |
response | message. See service definition for GetPositionFK for more information on this message. |
Definition at line 561 of file sr_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.
request | message. See service definition for GetPositionIK for more information on this message. |
response | message. 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.
KDL::Chain Kinematics::chain [private] |
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.
ros::ServiceServer Kinematics::fk_service [private] |
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.
ros::ServiceServer Kinematics::ik_service [private] |
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.
ros::NodeHandle Kinematics::nh [private] |
Definition at line 67 of file sr_kinematics.cpp.
ros::NodeHandle Kinematics::nh_private [private] |
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.
tf::TransformListener Kinematics::tf_listener [private] |
Definition at line 87 of file sr_kinematics.cpp.
std::string Kinematics::tip_name [private] |
Definition at line 68 of file sr_kinematics.cpp.