Public Types | Public Member Functions | Static Public Attributes | Protected Attributes | Private Member Functions
kinematics::KinematicsBase Class Reference

Provides an interface for kinematics solvers. More...

#include <kinematics_base.h>

Inheritance diagram for kinematics::KinematicsBase:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::function< void(const
geometry_msgs::Pose &ik_pose,
const std::vector< double >
&ik_solution,
moveit_msgs::MoveItErrorCodes
&error_code)> 
IKCallbackFn
 The signature for a callback that can compute IK.

Public Member Functions

virtual const std::string & getBaseFrame () const
 Return the name of the frame in which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.
double getDefaultTimeout () const
 For functions that require a timeout specified but one is not specified using arguments, this default timeout is used.
virtual const std::string & getGroupName () const
 Return the name of the group that the solver is operating on.
virtual const std::vector
< std::string > & 
getJointNames () const =0
 Return all the joint names in the order they are used internally.
virtual const std::vector
< std::string > & 
getLinkNames () const =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) const =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, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =0
 Given a desired pose of the end-effector, compute the joint angles to reach it.
virtual void getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const
 Get the set of redundant joints.
double getSearchDiscretization () const
 Get the value of the search discretization.
virtual const std::string & getTipFrame () const
 Return the name of the tip frame of the chain on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.
virtual bool initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)=0
 Initialization function for the kinematics.
 KinematicsBase ()
virtual bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =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, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =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, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =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, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =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).
void setDefaultTimeout (double timeout)
 For functions that require a timeout specified but one is not specified using arguments, a default timeout is used, as set by this function (and initialized to KinematicsBase::DEFAULT_TIMEOUT)
virtual bool setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices)
 Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK solver and choice of redundant joints!
bool setRedundantJoints (const std::vector< std::string > &redundant_joint_names)
 Set a set of redundant joints for the kinematics solver to use. This function is just a convenience function that calls the previous definition of setRedundantJoints()
void setSearchDiscretization (double sd)
 Set the search discretization.
virtual void setValues (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
 Set the parameters for the solver.
virtual ~KinematicsBase ()
 Virtual destructor for the interface.

Static Public Attributes

static const double DEFAULT_SEARCH_DISCRETIZATION = 0.1
static const double DEFAULT_TIMEOUT = 1.0

Protected Attributes

std::string base_frame_
double default_timeout_
std::string group_name_
std::vector< unsigned int > redundant_joint_indices_
std::string robot_description_
double search_discretization_
std::string tip_frame_

Private Member Functions

std::string removeSlash (const std::string &str) const

Detailed Description

Provides an interface for kinematics solvers.

Definition at line 71 of file kinematics_base.h.


Member Typedef Documentation

typedef boost::function<void(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> kinematics::KinematicsBase::IKCallbackFn

The signature for a callback that can compute IK.

Definition at line 79 of file kinematics_base.h.


Constructor & Destructor Documentation

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

Virtual destructor for the interface.

Definition at line 319 of file kinematics_base.h.

Definition at line 321 of file kinematics_base.h.


Member Function Documentation

virtual const std::string& kinematics::KinematicsBase::getBaseFrame ( ) const [inline, virtual]

Return the name of the frame in which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.

Returns:
The string name of the frame in which the solver is operating

Definition at line 237 of file kinematics_base.h.

For functions that require a timeout specified but one is not specified using arguments, this default timeout is used.

Definition at line 311 of file kinematics_base.h.

virtual const std::string& kinematics::KinematicsBase::getGroupName ( ) const [inline, virtual]

Return the name of the group that the solver is operating on.

Returns:
The string name of the group that the solver is operating on

Definition at line 228 of file kinematics_base.h.

virtual const std::vector<std::string>& kinematics::KinematicsBase::getJointNames ( ) const [pure virtual]

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

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

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

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

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

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

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

Parameters:
link_namesA set of links for which FK needs to be computed
joint_anglesThe state for which FK is being computed
posesThe resultant set of poses (in the frame returned by getBaseFrame())
Returns:
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

virtual bool kinematics::KinematicsBase::getPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [pure virtual]

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

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
lock_redundant_jointsif setRedundantJoints() was previously called, keep the values of the joints marked as redundant the same as in the seed
Returns:
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

virtual void kinematics::KinematicsBase::getRedundantJoints ( std::vector< unsigned int > &  redundant_joint_indices) const [inline, virtual]

Get the set of redundant joints.

Definition at line 272 of file kinematics_base.h.

Get the value of the search discretization.

Definition at line 298 of file kinematics_base.h.

virtual const std::string& kinematics::KinematicsBase::getTipFrame ( ) const [inline, virtual]

Return the name of the tip frame of the chain on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.

Returns:
The string name of the tip frame of the chain on which the solver is operating

Definition at line 246 of file kinematics_base.h.

virtual bool kinematics::KinematicsBase::initialize ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  base_frame,
const std::string &  tip_frame,
double  search_discretization 
) [pure virtual]

Initialization function for the kinematics.

Parameters:
robot_descriptionThis parameter can be used as an identifier for the robot kinematics is computed for; For example, rhe name of the ROS parameter that contains the robot description;
group_nameThe group for which this solver is being configured
base_frameThe base frame in which all input poses are expected. This may (or may not) be the root frame of the chain that the solver operates on
tip_frameThe tip of the chain
search_discretizationThe discretization of the search when the solver steps through the redundancy
Returns:
True if initialization was successful, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

std::string kinematics::KinematicsBase::removeSlash ( const std::string &  str) const [private]

Definition at line 83 of file kinematics_base.cpp.

virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [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
timeoutThe amount of time (in seconds) available to the solver
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
lock_redundant_jointsif setRedundantJoints() was previously called, keep the values of the joints marked as redundant the same as in the seed
Returns:
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [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
timeoutThe amount of time (in seconds) available to the solver
consistency_limitsthe distance that any joint in the solution can be from the corresponding joints in the current seed state
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
lock_redundant_jointsif setRedundantJoints() was previously called, keep the values of the joints marked as redundant the same as in the seed
Returns:
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [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
timeoutThe amount of time (in seconds) available to the solver
solutionthe solution vector
desired_pose_callbackA callback function for the desired link pose - could be used, e.g. to check for collisions for the end-effector
solution_callbackA callback solution for the IK solution
error_codean error code that encodes the reason for failure or success
lock_redundant_jointsif setRedundantJoints() was previously called, keep the values of the joints marked as redundant the same as in the seed
Returns:
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [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
timeoutThe amount of time (in seconds) available to the solver
consistency_limitsthe distance that any joint in the solution can be from the corresponding joints in the current seed state
solutionthe solution vector
desired_pose_callbackA callback function for the desired link pose - could be used, e.g. to check for collisions for the end-effector
solution_callbackA callback solution for the IK solution
error_codean error code that encodes the reason for failure or success
lock_redundant_jointsif setRedundantJoints() was previously called, keep the values of the joints marked as redundant the same as in the seed
Returns:
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

void kinematics::KinematicsBase::setDefaultTimeout ( double  timeout) [inline]

For functions that require a timeout specified but one is not specified using arguments, a default timeout is used, as set by this function (and initialized to KinematicsBase::DEFAULT_TIMEOUT)

Definition at line 305 of file kinematics_base.h.

bool kinematics::KinematicsBase::setRedundantJoints ( const std::vector< unsigned int > &  redundant_joint_indices) [virtual]

Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK solver and choice of redundant joints!

Parameters:
redundant_joint_indicesThe set of redundant joint indices (corresponding to the list of joints you get from getJointNames()).
Returns:
False if any of the input joint indices are invalid (exceed number of joints)

Definition at line 56 of file kinematics_base.cpp.

bool kinematics::KinematicsBase::setRedundantJoints ( const std::vector< std::string > &  redundant_joint_names)

Set a set of redundant joints for the kinematics solver to use. This function is just a convenience function that calls the previous definition of setRedundantJoints()

Parameters:
redundant_joint_namesThe set of redundant joint names.
Returns:
False if any of the input joint indices are invalid (exceed number of joints)

Definition at line 69 of file kinematics_base.cpp.

Set the search discretization.

Definition at line 290 of file kinematics_base.h.

void kinematics::KinematicsBase::setValues ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  base_frame,
const std::string &  tip_frame,
double  search_discretization 
) [virtual]

Set the parameters for the solver.

Parameters:
robot_descriptionThis parameter can be used as an identifier for the robot kinematics is computed for; For example, rhe name of the ROS parameter that contains the robot description;
group_nameThe group for which this solver is being configured
base_frameThe base frame in which all input poses are expected. This may (or may not) be the root frame of the chain that the solver operates on
tip_frameThe tip of the chain
search_discretizationThe discretization of the search when the solver steps through the redundancy

Definition at line 43 of file kinematics_base.cpp.


Member Data Documentation

std::string kinematics::KinematicsBase::base_frame_ [protected]

Definition at line 330 of file kinematics_base.h.

Definition at line 75 of file kinematics_base.h.

const double kinematics::KinematicsBase::DEFAULT_TIMEOUT = 1.0 [static]

Definition at line 76 of file kinematics_base.h.

Definition at line 333 of file kinematics_base.h.

std::string kinematics::KinematicsBase::group_name_ [protected]

Definition at line 329 of file kinematics_base.h.

std::vector<unsigned int> kinematics::KinematicsBase::redundant_joint_indices_ [protected]

Definition at line 334 of file kinematics_base.h.

Definition at line 328 of file kinematics_base.h.

Definition at line 332 of file kinematics_base.h.

std::string kinematics::KinematicsBase::tip_frame_ [protected]

Definition at line 331 of file kinematics_base.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:48