Public Member Functions | Private Member Functions | Private Attributes | List of all members
Kinematics Class Reference

Public Member Functions

bool init ()
 
 Kinematics ()
 

Private Member Functions

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)
 

Private Attributes

KDL::Chain_coupling chain
 
std::string finger_base_name
 
ros::ServiceServer fk_service
 
KDL::ChainFkSolverPos_recursivefk_solver
 
ros::ServiceServer ik_service
 
KDL::ChainIkSolverPos_NR_JL_couplingik_solver_pos
 
KDL::ChainIkSolverVel_wdls_couplingik_solver_vel
 
moveit_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
 

Detailed Description

Definition at line 155 of file hand_kinematics_coupling.cpp.

Constructor & Destructor Documentation

Kinematics::Kinematics ( )

Definition at line 213 of file hand_kinematics_coupling.cpp.

Member Function Documentation

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
Jointvector to be initialized with random values.

Definition at line 482 of file hand_kinematics_coupling.cpp.

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

Definition at line 456 of file hand_kinematics_coupling.cpp.

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

Definition at line 468 of file hand_kinematics_coupling.cpp.

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
Arequest message. See service definition for GetPositionFK for more information on this message.
Theresponse 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
Arequest message. See service definition for GetPositionIK for more information on this message.
Theresponse 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 ( )

Definition at line 217 of file hand_kinematics_coupling.cpp.

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

Definition at line 356 of file hand_kinematics_coupling.cpp.

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

Definition at line 385 of file hand_kinematics_coupling.cpp.

Member Data Documentation

KDL::Chain_coupling Kinematics::chain
private

Definition at line 166 of file hand_kinematics_coupling.cpp.

std::string Kinematics::finger_base_name
private

Definition at line 164 of file hand_kinematics_coupling.cpp.

ros::ServiceServer Kinematics::fk_service
private

Definition at line 174 of file hand_kinematics_coupling.cpp.

KDL::ChainFkSolverPos_recursive* Kinematics::fk_solver
private

Definition at line 169 of file hand_kinematics_coupling.cpp.

ros::ServiceServer Kinematics::ik_service
private

Definition at line 173 of file hand_kinematics_coupling.cpp.

KDL::ChainIkSolverPos_NR_JL_coupling* Kinematics::ik_solver_pos
private

Definition at line 170 of file hand_kinematics_coupling.cpp.

KDL::ChainIkSolverVel_wdls_coupling* Kinematics::ik_solver_vel
private

Definition at line 171 of file hand_kinematics_coupling.cpp.

moveit_msgs::KinematicSolverInfo Kinematics::info
private

Definition at line 178 of file hand_kinematics_coupling.cpp.

KDL::JntArray Kinematics::joint_max
private

Definition at line 165 of file hand_kinematics_coupling.cpp.

KDL::JntArray Kinematics::joint_min
private

Definition at line 165 of file hand_kinematics_coupling.cpp.

ros::NodeHandle Kinematics::nh
private

Definition at line 163 of file hand_kinematics_coupling.cpp.

ros::NodeHandle Kinematics::nh_private
private

Definition at line 163 of file hand_kinematics_coupling.cpp.

unsigned int Kinematics::num_joints
private

Definition at line 167 of file hand_kinematics_coupling.cpp.

std::string Kinematics::root_name
private

Definition at line 164 of file hand_kinematics_coupling.cpp.

tf::TransformListener Kinematics::tf_listener
private

Definition at line 176 of file hand_kinematics_coupling.cpp.

std::string Kinematics::tip_name
private

Definition at line 164 of file hand_kinematics_coupling.cpp.


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


hand_kinematics
Author(s): Juan Antonio Corrales Ramon (UPMC),, Guillaume Walck (CITEC)
autogenerated on Wed Oct 14 2020 04:05:07