Public Member Functions | Protected Member Functions
kinematics::KinematicsBase Class Reference

Provides an interface for kinematics solvers. More...

#include <kinematics_base.h>

List of all members.

Public Member Functions

virtual std::string getBaseFrame ()=0
 Return the frame in which the kinematics is operating.
virtual std::vector< std::string > getJointNames ()=0
 Return all the joint names in the order they are used internally.
virtual std::vector< std::string > getLinkNames ()=0
 Return all the link names in the order they are represented internally.
virtual bool getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses)=0
 Given a set of joint angles and a set of links, compute their pose.
virtual bool getPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, int &error_code)=0
 Given a desired pose of the end-effector, compute the joint angles to reach it.
virtual std::string getToolFrame ()=0
 Return the links for which kinematics can be computed.
virtual bool initialize (std::string name)=0
 Initialization function for the kinematics.
virtual bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, const double &timeout, std::vector< double > &solution, int &error_code)=0
 Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
virtual bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, const double &timeout, std::vector< double > &solution, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &desired_pose_callback, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &solution_callback, int &error_code)=0
 Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
virtual ~KinematicsBase ()
 Virtual destructor for the interface.

Protected Member Functions

 KinematicsBase ()

Detailed Description

Provides an interface for kinematics solvers.

Definition at line 63 of file kinematics_base.h.


Constructor & Destructor Documentation

virtual kinematics::KinematicsBase::~KinematicsBase ( ) [inline, virtual]

Virtual destructor for the interface.

Definition at line 147 of file kinematics_base.h.

Definition at line 150 of file kinematics_base.h.


Member Function Documentation

virtual std::string kinematics::KinematicsBase::getBaseFrame ( ) [pure virtual]

Return the frame in which the kinematics is operating.

Returns:
the string name of the frame in which the kinematics is operating
virtual std::vector<std::string> kinematics::KinematicsBase::getJointNames ( ) [pure virtual]

Return all the joint names in the order they are used internally.

virtual std::vector<std::string> kinematics::KinematicsBase::getLinkNames ( ) [pure virtual]

Return all the link names in the order they are represented internally.

virtual bool kinematics::KinematicsBase::getPositionFK ( const std::vector< std::string > &  link_names,
const std::vector< double > &  joint_angles,
std::vector< geometry_msgs::Pose > &  poses 
) [pure virtual]

Given a set of joint angles and a set of links, compute their pose.

Parameters:
request- the request contains the joint angles, set of links for which poses are to be computed and a timeout
response- the response contains stamped pose information for all the requested links
Returns:
True if a valid solution was found, false otherwise
virtual bool kinematics::KinematicsBase::getPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
int &  error_code 
) [pure virtual]

Given a desired pose of the end-effector, compute the joint angles to reach it.

Parameters:
ik_link_name- the name of the link for which IK is being computed
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise
virtual std::string kinematics::KinematicsBase::getToolFrame ( ) [pure virtual]

Return the links for which kinematics can be computed.

virtual bool kinematics::KinematicsBase::initialize ( std::string  name) [pure virtual]

Initialization function for the kinematics.

Returns:
True if initialization was successful, false otherwise
virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
std::vector< double > &  solution,
int &  error_code 
) [pure virtual]

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise
virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
std::vector< double > &  solution,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  desired_pose_callback,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  solution_callback,
int &  error_code 
) [pure virtual]

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise

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


kinematics_base
Author(s): Sachin Chitta
autogenerated on Tue Jan 7 2014 11:18:53