|
| void | generateRandomJntSeed (KDL::JntArray &jnt_pos_in) |
| | This method generates a random joint array vector between the joint limits so that local minima in IK can be avoided. More...
|
| |
| int | getJointIndex (const std::string &name) |
| |
| int | getKDLSegmentIndex (const std::string &name) |
| |
| bool | getPositionFK (moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response) |
| | This is the basic forward kinematics service that will return information about the kinematics node. More...
|
| |
| bool | getPositionIK (moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response) |
| | This is the basic IK service method that will compute and return an IK solution. More...
|
| |
| bool | loadModel (const std::string xml) |
| |
| bool | readJoints (urdf::Model &robot_model) |
| |
| Kinematics::Kinematics |
( |
| ) |
|
| void Kinematics::generateRandomJntSeed |
( |
KDL::JntArray & |
jnt_pos_in | ) |
|
|
private |
This method generates a random joint array vector between the joint limits so that local minima in IK can be avoided.
- Parameters
-
| Joint | vector to be initialized with random values. |
Definition at line 482 of file hand_kinematics_coupling.cpp.
| int Kinematics::getJointIndex |
( |
const std::string & |
name | ) |
|
|
private |
| int Kinematics::getKDLSegmentIndex |
( |
const std::string & |
name | ) |
|
|
private |
| bool Kinematics::getPositionFK |
( |
moveit_msgs::GetPositionFK::Request & |
request, |
|
|
moveit_msgs::GetPositionFK::Response & |
response |
|
) |
| |
|
private |
This is the basic forward kinematics service that will return information about the kinematics node.
- Parameters
-
| 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 584 of file hand_kinematics_coupling.cpp.
| bool Kinematics::getPositionIK |
( |
moveit_msgs::GetPositionIK::Request & |
request, |
|
|
moveit_msgs::GetPositionIK::Response & |
response |
|
) |
| |
|
private |
This is the basic IK service method that will compute and return an IK solution.
- Parameters
-
| 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 493 of file hand_kinematics_coupling.cpp.
| bool Kinematics::init |
( |
| ) |
|
| bool Kinematics::loadModel |
( |
const std::string |
xml | ) |
|
|
private |
| bool Kinematics::readJoints |
( |
urdf::Model & |
robot_model | ) |
|
|
private |
| std::string Kinematics::finger_base_name |
|
private |
| moveit_msgs::KinematicSolverInfo Kinematics::info |
|
private |
| unsigned int Kinematics::num_joints |
|
private |
| std::string Kinematics::root_name |
|
private |
| std::string Kinematics::tip_name |
|
private |
The documentation for this class was generated from the following file: