Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Namespaces | Classes | Typedefs | Functions | Variables
tesseract_kinematics Namespace Reference

Namespaces

namespace  test_suite
 

Classes

class  AbbIRB2400Kinematics
 
class  ForwardKinematics
 Forward kinematics functions. More...
 
class  FwdKinFactory
 Define a forward kinematics plugin which the factory can create an instance. More...
 
class  iiwa7Kinematics
 
class  IKFastInvKin
 IKFast Inverse Kinematics Implmentation. More...
 
class  InverseKinematics
 Inverse kinematics functions. More...
 
class  InvKinFactory
 Define a inverse kinematics plugin which the factory can create an instance. More...
 
class  JointGroup
 A Joint Group is defined by a list of joint_names. More...
 
struct  KDLChainData
 The KDLChainData struct. More...
 
class  KDLFwdKinChain
 KDL kinematic chain implementation. More...
 
class  KDLFwdKinChainFactory
 
class  KDLInvKinChainLMA
 KDL Inverse kinematic chain implementation. More...
 
class  KDLInvKinChainLMAFactory
 
class  KDLInvKinChainNR
 KDL Inverse kinematic chain implementation. More...
 
class  KDLInvKinChainNRFactory
 
class  KinematicGroup
 
class  KinematicsPluginFactory
 
struct  KinGroupIKInput
 Structure containing the data required to solve inverse kinematics. More...
 
struct  Manipulability
 Contains both manipulability ellipsoid and force ellipsoid data. More...
 
struct  ManipulabilityEllipsoid
 Used to store Manipulability and Force Ellipsoid data. More...
 
class  OPWInvKin
 OPW Inverse Kinematics Implementation. More...
 
class  OPWInvKinFactory
 
class  REPInvKin
 Robot With External Positioner Inverse kinematic implementation. More...
 
class  REPInvKinFactory
 
class  ROPInvKin
 Robot on Positioner Inverse kinematic implementation. More...
 
class  ROPInvKinFactory
 
class  URInvKin
 Universal Robot Inverse Kinematics Implementation. More...
 
class  URInvKinFactory
 
struct  URParameters
 The Universal Robot kinematic parameters. More...
 

Typedefs

using KinGroupIKInputs = tesseract_common::AlignedVector< KinGroupIKInput >
 
using IKSolutions = std::vector< Eigen::VectorXd >
 The inverse kinematics solutions container. More...
 
template<typename FloatType >
using VectorX = Eigen::Matrix< FloatType, Eigen::Dynamic, 1 >
 

Functions

static const URParameters UR10Parameters (0.1273, -0.612, -0.5723, 0.163941, 0.1157, 0.0922)
 The UR10 kinematic parameters. More...
 
static const URParameters UR5Parameters (0.089159, -0.42500, -0.39225, 0.10915, 0.09465, 0.0823)
 The UR5 kinematic parameters. More...
 
static const URParameters UR3Parameters (0.1519, -0.24365, -0.21325, 0.11235, 0.08535, 0.0819)
 The UR3 kinematic parameters. More...
 
static const URParameters UR10eParameters (0.1807, -0.6127, -0.57155, 0.17415, 0.11985, 0.11655)
 The UR10e kinematic parameters. More...
 
static const URParameters UR5eParameters (0.1625, -0.425, -0.3922, 0.1333, 0.0997, 0.0996)
 The UR5e kinematic parameters. More...
 
static const URParameters UR3eParameters (0.15185, -0.24355, -0.2132, 0.13105, 0.08535, 0.0921)
 The UR3e kinematic parameters. More...
 
static void numericalJacobian (Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Isometry3d &change_base, const tesseract_kinematics::ForwardKinematics &kin, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const Eigen::Ref< const Eigen::Vector3d > &link_point)
 Numerically calculate a jacobian. This is mainly used for testing. More...
 
static void numericalJacobian (Eigen::Ref< Eigen::MatrixXd > jacobian, const JointGroup &joint_group, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const Eigen::Ref< const Eigen::Vector3d > &link_point)
 Numerically calculate a jacobian. This is mainly used for testing. More...
 
static bool solvePInv (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, Eigen::Ref< Eigen::VectorXd > x)
 Solve equation Ax=b for x Use this SVD to compute A+ (pseudoinverse of A). Weighting still TBD. More...
 
static bool dampedPInv (const Eigen::Ref< const Eigen::MatrixXd > &A, Eigen::Ref< Eigen::MatrixXd > P, const double eps=0.011, const double lambda=0.01)
 Calculate Damped Pseudoinverse Use this SVD to compute A+ (pseudoinverse of A). Weighting still TBD. More...
 
bool isNearSingularity (const Eigen::Ref< const Eigen::MatrixXd > &jacobian, double threshold=0.01)
 Check if the provided jacobian is near a singularity. More...
 
Manipulability calcManipulability (const Eigen::Ref< const Eigen::MatrixXd > &jacobian)
 Calculate manipulability data about the provided jacobian. More...
 
template<typename FloatType >
void getRedundantSolutionsHelper (std::vector< VectorX< FloatType > > &redundant_sols, const Eigen::Ref< const Eigen::VectorXd > &sol, const Eigen::MatrixX2d &limits, std::vector< Eigen::Index >::const_iterator current_index, std::vector< Eigen::Index >::const_iterator end_index)
 This a recursive function for calculating all permutations of the redundant solutions. More...
 
template<typename FloatType >
std::vector< VectorX< FloatType > > getRedundantSolutions (const Eigen::Ref< const VectorX< FloatType > > &sol, const Eigen::MatrixX2d &limits, const std::vector< Eigen::Index > &redundancy_capable_joints)
 Kinematics only return solution between PI and -PI. Provided the limits it will append redundant solutions. More...
 
template<typename FloatType >
bool isValid (const std::array< FloatType, 6 > &qs)
 Given a vector of floats, this check if they are finite. More...
 
template<typename FloatType >
void harmonizeTowardZero (Eigen::Ref< VectorX< FloatType > > qs, const std::vector< Eigen::Index > &redundancy_capable_joints)
 This take an array of floats and modifies them in place to be between [-PI, PI]. More...
 
bool checkKinematics (const KinematicGroup &manip, double tol=1e-3)
 This compares calcFwdKin to calcInvKin for a KinematicGroup. More...
 
void KDLToEigen (const KDL::Frame &frame, Eigen::Isometry3d &transform)
 Convert KDL::Frame to Eigen::Isometry3d. More...
 
void EigenToKDL (const Eigen::Isometry3d &transform, KDL::Frame &frame)
 Convert Eigen::Isometry3d to KDL::Frame. More...
 
void KDLToEigen (const KDL::Jacobian &jacobian, Eigen::Ref< Eigen::MatrixXd > matrix)
 Convert KDL::Jacobian to Eigen::Matrix. More...
 
void KDLToEigen (const KDL::Jacobian &jacobian, const std::vector< int > &q_nrs, Eigen::Ref< Eigen::MatrixXd > matrix)
 Convert a subset of KDL::Jacobian to Eigen::Matrix. More...
 
void EigenToKDL (const Eigen::Ref< const Eigen::VectorXd > &vec, KDL::JntArray &joints)
 Convert Eigen::Vector to KDL::JntArray. More...
 
void KDLToEigen (const KDL::JntArray &joints, Eigen::Ref< Eigen::VectorXd > vec)
 Convert KDL::JntArray to Eigen::Vector. More...
 
bool parseSceneGraph (KDLChainData &results, const tesseract_scene_graph::SceneGraph &scene_graph, const std::vector< std::pair< std::string, std::string > > &chains)
 Parse KDL chain data from the scene graph. More...
 
bool parseSceneGraph (KDLChainData &results, const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &base_name, const std::string &tip_name)
 Parse KDL chain data from the scene graph. More...
 
int inverse (const Eigen::Isometry3d &T, const URParameters &params, double *q_sols, double q6_des)
 

Variables

static const std::string DEFAULT_REP_INV_KIN_SOLVER_NAME = "REPInvKin"
 
static const std::string DEFAULT_ROP_INV_KIN_SOLVER_NAME = "ROPInvKin"
 
static const std::string IKFAST_INV_KIN_CHAIN_SOLVER_NAME = "IKFastInvKin"
 
static const std::string KDL_FWD_KIN_CHAIN_SOLVER_NAME = "KDLFwdKinChain"
 
static const std::string KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME = "KDLInvKinChainLMA"
 
static const std::string KDL_INV_KIN_CHAIN_NR_SOLVER_NAME = "KDLInvKinChainNR"
 
static const std::string OPW_INV_KIN_CHAIN_SOLVER_NAME = "OPWInvKin"
 
static const std::string UR_INV_KIN_CHAIN_SOLVER_NAME = "URInvKin"
 

Typedef Documentation

◆ IKSolutions

using tesseract_kinematics::IKSolutions = typedef std::vector<Eigen::VectorXd>

The inverse kinematics solutions container.

◆ KinGroupIKInputs

◆ VectorX

template<typename FloatType >
using tesseract_kinematics::VectorX = typedef Eigen::Matrix<FloatType, Eigen::Dynamic, 1>

Function Documentation

◆ calcManipulability()

Manipulability tesseract_kinematics::calcManipulability ( const Eigen::Ref< const Eigen::MatrixXd > &  jacobian)
inline

Calculate manipulability data about the provided jacobian.

Parameters
jacobianThe jacobian used to calculate manipulability
Returns
The manipulability data

◆ checkKinematics()

bool tesseract_kinematics::checkKinematics ( const KinematicGroup manip,
double  tol = 1e-3 
)

This compares calcFwdKin to calcInvKin for a KinematicGroup.

It checks that the following are the same:

  • The forward kinematic solution matches the inverse kinematic solutions
    Parameters
    manipThe kinematic group for a manipulator
    Returns
    True it they match, otherwise false.

◆ dampedPInv()

static bool tesseract_kinematics::dampedPInv ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
Eigen::Ref< Eigen::MatrixXd >  P,
const double  eps = 0.011,
const double  lambda = 0.01 
)
inlinestatic

Calculate Damped Pseudoinverse Use this SVD to compute A+ (pseudoinverse of A). Weighting still TBD.

Parameters
AInput matrix (represents Jacobian)
POutput matrix (represents pseudoinverse of A)
epsSingular value threshold
lambdaDamping factor
Returns
True if Pseudoinverse completes properly

◆ EigenToKDL() [1/2]

void tesseract_kinematics::EigenToKDL ( const Eigen::Isometry3d &  transform,
KDL::Frame &  frame 
)

Convert Eigen::Isometry3d to KDL::Frame.

Parameters
transformInput Eigen transform (Isometry3d)
frameOutput KDL Frame

◆ EigenToKDL() [2/2]

void tesseract_kinematics::EigenToKDL ( const Eigen::Ref< const Eigen::VectorXd > &  vec,
KDL::JntArray &  joints 
)

Convert Eigen::Vector to KDL::JntArray.

Parameters
vecInput Eigen vector
jointsOutput KDL joint array

◆ getRedundantSolutions()

template<typename FloatType >
std::vector< VectorX< FloatType > > tesseract_kinematics::getRedundantSolutions ( const Eigen::Ref< const VectorX< FloatType > > &  sol,
const Eigen::MatrixX2d &  limits,
const std::vector< Eigen::Index > &  redundancy_capable_joints 
)
inline

Kinematics only return solution between PI and -PI. Provided the limits it will append redundant solutions.

The list of redundant solutions does not include the provided solutions.

Parameters
solThe solution to calculate redundant solutions about
limitsThe joint limits of the robot
redundancy_capable_jointsThe indices of the redundancy capable joints

◆ getRedundantSolutionsHelper()

template<typename FloatType >
void tesseract_kinematics::getRedundantSolutionsHelper ( std::vector< VectorX< FloatType > > &  redundant_sols,
const Eigen::Ref< const Eigen::VectorXd > &  sol,
const Eigen::MatrixX2d &  limits,
std::vector< Eigen::Index >::const_iterator  current_index,
std::vector< Eigen::Index >::const_iterator  end_index 
)
inline

This a recursive function for calculating all permutations of the redundant solutions.

This should not be used directly, use getRedundantSolutions function.

◆ harmonizeTowardZero()

template<typename FloatType >
void tesseract_kinematics::harmonizeTowardZero ( Eigen::Ref< VectorX< FloatType > >  qs,
const std::vector< Eigen::Index > &  redundancy_capable_joints 
)
inline

This take an array of floats and modifies them in place to be between [-PI, PI].

Parameters
qsA pointer to a float array
dofThe length of the float array

◆ inverse()

int tesseract_kinematics::inverse ( const Eigen::Isometry3d &  T,
const URParameters params,
double *  q_sols,
double  q6_des 
)

◆ isNearSingularity()

bool tesseract_kinematics::isNearSingularity ( const Eigen::Ref< const Eigen::MatrixXd > &  jacobian,
double  threshold = 0.01 
)
inline

Check if the provided jacobian is near a singularity.

This is keep separated from the forward kinematics because special consideration may need to be made based on the kinematics arrangement.

Parameters
jacobianThe jacobian to check if near a singularity
thresholdThe threshold that all singular values must be greater than or equal to not be considered near a singularity

◆ isValid()

template<typename FloatType >
bool tesseract_kinematics::isValid ( const std::array< FloatType, 6 > &  qs)
inline

Given a vector of floats, this check if they are finite.

In the case of OPW and IKFast they can return NANS so this is used to check that solutions are valid.

Parameters
qsA pointer to a floats array
dofThe length of the float array
Returns
True if the array is valid, otherwise false

◆ KDLToEigen() [1/4]

void tesseract_kinematics::KDLToEigen ( const KDL::Frame &  frame,
Eigen::Isometry3d &  transform 
)

Convert KDL::Frame to Eigen::Isometry3d.

Parameters
frameInput KDL Frame
transformOutput Eigen transform (Isometry3d)

◆ KDLToEigen() [2/4]

void tesseract_kinematics::KDLToEigen ( const KDL::Jacobian &  jacobian,
const std::vector< int > &  q_nrs,
Eigen::Ref< Eigen::MatrixXd >  matrix 
)

Convert a subset of KDL::Jacobian to Eigen::Matrix.

Parameters
jacobianInput KDL Jacobian
q_nrsInput the columns to use
matrixOutput Eigen MatrixXd

◆ KDLToEigen() [3/4]

void tesseract_kinematics::KDLToEigen ( const KDL::Jacobian &  jacobian,
Eigen::Ref< Eigen::MatrixXd >  matrix 
)

Convert KDL::Jacobian to Eigen::Matrix.

Parameters
jacobianInput KDL Jacobian
matrixOutput Eigen MatrixXd

◆ KDLToEigen() [4/4]

void tesseract_kinematics::KDLToEigen ( const KDL::JntArray &  joints,
Eigen::Ref< Eigen::VectorXd >  vec 
)

Convert KDL::JntArray to Eigen::Vector.

Parameters
jointsInput KDL joint array
vecOutput Eigen vector

◆ numericalJacobian() [1/2]

static void tesseract_kinematics::numericalJacobian ( Eigen::Ref< Eigen::MatrixXd >  jacobian,
const Eigen::Isometry3d &  change_base,
const tesseract_kinematics::ForwardKinematics kin,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const std::string &  link_name,
const Eigen::Ref< const Eigen::Vector3d > &  link_point 
)
inlinestatic

Numerically calculate a jacobian. This is mainly used for testing.

Parameters
jacobian(Return) The jacobian which gets filled out.
kinThe kinematics object
joint_valuesThe joint values for which to calculate the jacobian
link_nameThe link_name for which the jacobian should be calculated
link_pointThe point on the link for which to calculate the jacobian

◆ numericalJacobian() [2/2]

static void tesseract_kinematics::numericalJacobian ( Eigen::Ref< Eigen::MatrixXd >  jacobian,
const JointGroup joint_group,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const std::string &  link_name,
const Eigen::Ref< const Eigen::Vector3d > &  link_point 
)
inlinestatic

Numerically calculate a jacobian. This is mainly used for testing.

Parameters
jacobian(Return) The jacobian which gets filled out.
joint_groupThe joint group object
joint_valuesThe joint values for which to calculate the jacobian
link_nameThe link_name for which the jacobian should be calculated
link_pointThe point on the link for which to calculate the jacobian

◆ parseSceneGraph() [1/2]

bool tesseract_kinematics::parseSceneGraph ( KDLChainData results,
const tesseract_scene_graph::SceneGraph scene_graph,
const std::string &  base_name,
const std::string &  tip_name 
)

Parse KDL chain data from the scene graph.

Parameters
resultsKDL Chain data
scene_graphThe Scene Graph
base_nameThe base link name of chain
tip_nameThe tip link name of chain
Returns
True if successful otherwise false

◆ parseSceneGraph() [2/2]

bool tesseract_kinematics::parseSceneGraph ( KDLChainData results,
const tesseract_scene_graph::SceneGraph scene_graph,
const std::vector< std::pair< std::string, std::string > > &  chains 
)

Parse KDL chain data from the scene graph.

Parameters
resultsKDL Chain data
scene_graphThe Scene Graph
chainsA vector of link pairs that represent a chain which all get concatenated together. The firts link should be the base link and the second link should the tip link of the chain.
Returns
True if successful otherwise false

◆ solvePInv()

static bool tesseract_kinematics::solvePInv ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::VectorXd > &  b,
Eigen::Ref< Eigen::VectorXd >  x 
)
inlinestatic

Solve equation Ax=b for x Use this SVD to compute A+ (pseudoinverse of A). Weighting still TBD.

Parameters
AInput matrix (represents Jacobian)
bInput vector (represents desired pose)
xOutput vector (represents joint values)
Returns
True if solver completes properly

◆ UR10eParameters()

static const URParameters tesseract_kinematics::UR10eParameters ( 0.  1807,
-0.  6127,
-0.  57155,
0.  17415,
0.  11985,
0.  11655 
)
static

The UR10e kinematic parameters.

◆ UR10Parameters()

static const URParameters tesseract_kinematics::UR10Parameters ( 0.  1273,
-0.  612,
-0.  5723,
0.  163941,
0.  1157,
0.  0922 
)
static

The UR10 kinematic parameters.

◆ UR3eParameters()

static const URParameters tesseract_kinematics::UR3eParameters ( 0.  15185,
-0.  24355,
-0.  2132,
0.  13105,
0.  08535,
0.  0921 
)
static

The UR3e kinematic parameters.

◆ UR3Parameters()

static const URParameters tesseract_kinematics::UR3Parameters ( 0.  1519,
-0.  24365,
-0.  21325,
0.  11235,
0.  08535,
0.  0819 
)
static

The UR3 kinematic parameters.

◆ UR5eParameters()

static const URParameters tesseract_kinematics::UR5eParameters ( 0.  1625,
-0.  425,
-0.  3922,
0.  1333,
0.  0997,
0.  0996 
)
static

The UR5e kinematic parameters.

◆ UR5Parameters()

static const URParameters tesseract_kinematics::UR5Parameters ( 0.  089159,
-0.  42500,
-0.  39225,
0.  10915,
0.  09465,
0.  0823 
)
static

The UR5 kinematic parameters.

Variable Documentation

◆ DEFAULT_REP_INV_KIN_SOLVER_NAME

const std::string tesseract_kinematics::DEFAULT_REP_INV_KIN_SOLVER_NAME = "REPInvKin"
static

◆ DEFAULT_ROP_INV_KIN_SOLVER_NAME

const std::string tesseract_kinematics::DEFAULT_ROP_INV_KIN_SOLVER_NAME = "ROPInvKin"
static

◆ IKFAST_INV_KIN_CHAIN_SOLVER_NAME

const std::string tesseract_kinematics::IKFAST_INV_KIN_CHAIN_SOLVER_NAME = "IKFastInvKin"
static

◆ KDL_FWD_KIN_CHAIN_SOLVER_NAME

const std::string tesseract_kinematics::KDL_FWD_KIN_CHAIN_SOLVER_NAME = "KDLFwdKinChain"
static

◆ KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME

const std::string tesseract_kinematics::KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME = "KDLInvKinChainLMA"
static

◆ KDL_INV_KIN_CHAIN_NR_SOLVER_NAME

const std::string tesseract_kinematics::KDL_INV_KIN_CHAIN_NR_SOLVER_NAME = "KDLInvKinChainNR"
static

◆ OPW_INV_KIN_CHAIN_SOLVER_NAME

const std::string tesseract_kinematics::OPW_INV_KIN_CHAIN_SOLVER_NAME = "OPWInvKin"
static

◆ UR_INV_KIN_CHAIN_SOLVER_NAME

const std::string tesseract_kinematics::UR_INV_KIN_CHAIN_SOLVER_NAME = "URInvKin"
static