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

List of all members.

Classes

class  InitFailed

Public Member Functions

 Kinematics ()

Private Member Functions

double calculateEps (const KDL::Frame &f, const KDL::Frame &ref, const Eigen::MatrixXd &weight=Eigen::MatrixXd::Identity(6, 6))
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 getWeightedIK (kdl_arm_kinematics::GetWeightedIK::Request &request, kdl_arm_kinematics::GetWeightedIK::Response &response)
void initializeWeights (const kdl_arm_kinematics::KDLWeights &msg, Eigen::MatrixXd &weight_ts, Eigen::MatrixXd &weight_js, double &lambda)
bool loadModel (const std::string xml)
void parseWeightParams (ros::NodeHandle &nh)
bool readJoints (urdf::Model &robot_model)
bool solveCartToJnt (const KDL::JntArray &q_init, const KDL::Frame &q_in, KDL::JntArray &q_out, const KDL::Frame &tool_frame=KDL::Frame::Identity())
bool solveCartToJnt (const KDL::JntArray &q_init, const KDL::Frame &q_in, KDL::JntArray &q_out, const KDL::Frame &tool_frame, const Eigen::MatrixXd &weight_ts, const Eigen::MatrixXd &weight_js, const double lambda)

Private Attributes

KDL::Chain chain
double default_lambda
Eigen::MatrixXd default_weight_js
Eigen::MatrixXd default_weight_ts
double epsilon
ros::ServiceServer fk_service
ros::ServiceServer fk_solver_info_service
ros::ServiceServer ik_service
ros::ServiceServer ik_solver_info_service
kinematics_msgs::KinematicSolverInfo info
KDL::JntArray joint_max
KDL::JntArray joint_min
int max_iterations
ros::NodeHandle nh
ros::NodeHandle nh_private
unsigned int num_joints
std::string root_name
tf::TransformListener tf_listener
std::string tip_name
ros::ServiceServer weighted_ik_service

Detailed Description

Definition at line 25 of file arm_kinematics.cpp.


Constructor & Destructor Documentation

Definition at line 110 of file arm_kinematics.cpp.


Member Function Documentation

double Kinematics::calculateEps ( const KDL::Frame f,
const KDL::Frame ref,
const Eigen::MatrixXd &  weight = Eigen::MatrixXd::Identity(6,6) 
) [private]

Definition at line 391 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.

Parameters:
Arequest message. See service definition for GetKinematicSolverInfo for more information on this message.
Theresponse message. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 507 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.

Parameters:
Arequest message. See service definition for GetKinematicSolverInfo for more information on this message.
Theresponse message. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 501 of file arm_kinematics.cpp.

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

Definition at line 304 of file arm_kinematics.cpp.

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

Definition at line 312 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.

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 513 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.

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 442 of file arm_kinematics.cpp.

bool Kinematics::getWeightedIK ( kdl_arm_kinematics::GetWeightedIK::Request &  request,
kdl_arm_kinematics::GetWeightedIK::Response &  response 
) [private]

Get the weight matrices

Definition at line 559 of file arm_kinematics.cpp.

void Kinematics::initializeWeights ( const kdl_arm_kinematics::KDLWeights &  msg,
Eigen::MatrixXd &  weight_ts,
Eigen::MatrixXd &  weight_js,
double &  lambda 
) [private]

Definition at line 413 of file arm_kinematics.cpp.

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

Definition at line 218 of file arm_kinematics.cpp.

Definition at line 150 of file arm_kinematics.cpp.

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

Definition at line 243 of file arm_kinematics.cpp.

bool Kinematics::solveCartToJnt ( const KDL::JntArray &  q_init,
const KDL::Frame q_in,
KDL::JntArray &  q_out,
const KDL::Frame tool_frame = KDL::Frame::Identity() 
) [private]

Definition at line 323 of file arm_kinematics.cpp.

bool Kinematics::solveCartToJnt ( const KDL::JntArray &  q_init,
const KDL::Frame q_in,
KDL::JntArray &  q_out,
const KDL::Frame tool_frame,
const Eigen::MatrixXd &  weight_ts,
const Eigen::MatrixXd &  weight_js,
const double  lambda 
) [private]

Definition at line 330 of file arm_kinematics.cpp.


Member Data Documentation

Definition at line 41 of file arm_kinematics.cpp.

double Kinematics::default_lambda [private]

Definition at line 47 of file arm_kinematics.cpp.

Eigen::MatrixXd Kinematics::default_weight_js [private]

Definition at line 46 of file arm_kinematics.cpp.

Eigen::MatrixXd Kinematics::default_weight_ts [private]

Definition at line 45 of file arm_kinematics.cpp.

double Kinematics::epsilon [private]

Definition at line 44 of file arm_kinematics.cpp.

Definition at line 50 of file arm_kinematics.cpp.

Definition at line 50 of file arm_kinematics.cpp.

Definition at line 49 of file arm_kinematics.cpp.

Definition at line 49 of file arm_kinematics.cpp.

kinematics_msgs::KinematicSolverInfo Kinematics::info [private]

Definition at line 55 of file arm_kinematics.cpp.

KDL::JntArray Kinematics::joint_max [private]

Definition at line 40 of file arm_kinematics.cpp.

KDL::JntArray Kinematics::joint_min [private]

Definition at line 40 of file arm_kinematics.cpp.

Definition at line 43 of file arm_kinematics.cpp.

Definition at line 38 of file arm_kinematics.cpp.

Definition at line 38 of file arm_kinematics.cpp.

unsigned int Kinematics::num_joints [private]

Definition at line 42 of file arm_kinematics.cpp.

std::string Kinematics::root_name [private]

Definition at line 39 of file arm_kinematics.cpp.

Definition at line 53 of file arm_kinematics.cpp.

std::string Kinematics::tip_name [private]

Definition at line 39 of file arm_kinematics.cpp.

Definition at line 51 of file arm_kinematics.cpp.


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


kdl_arm_kinematics
Author(s): David Lu!!, Lorenz Moesenlechner
autogenerated on Sun Jan 26 2014 12:29:39