![]() |
Tesseract
Motion Planning Environment
|
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 ¶ms, 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" |
| using tesseract_kinematics::IKSolutions = typedef std::vector<Eigen::VectorXd> |
The inverse kinematics solutions container.
| using tesseract_kinematics::KinGroupIKInputs = typedef tesseract_common::AlignedVector<KinGroupIKInput> |
| using tesseract_kinematics::VectorX = typedef Eigen::Matrix<FloatType, Eigen::Dynamic, 1> |
|
inline |
Calculate manipulability data about the provided jacobian.
| jacobian | The jacobian used to calculate manipulability |
| 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:
| manip | The kinematic group for a manipulator |
|
inlinestatic |
Calculate Damped Pseudoinverse Use this SVD to compute A+ (pseudoinverse of A). Weighting still TBD.
| A | Input matrix (represents Jacobian) |
| P | Output matrix (represents pseudoinverse of A) |
| eps | Singular value threshold |
| lambda | Damping factor |
| void tesseract_kinematics::EigenToKDL | ( | const Eigen::Isometry3d & | transform, |
| KDL::Frame & | frame | ||
| ) |
Convert Eigen::Isometry3d to KDL::Frame.
| transform | Input Eigen transform (Isometry3d) |
| frame | Output KDL Frame |
| void tesseract_kinematics::EigenToKDL | ( | const Eigen::Ref< const Eigen::VectorXd > & | vec, |
| KDL::JntArray & | joints | ||
| ) |
Convert Eigen::Vector to KDL::JntArray.
| vec | Input Eigen vector |
| joints | Output KDL joint array |
|
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.
| sol | The solution to calculate redundant solutions about |
| limits | The joint limits of the robot |
| redundancy_capable_joints | The indices of the redundancy capable joints |
|
inline |
This a recursive function for calculating all permutations of the redundant solutions.
This should not be used directly, use getRedundantSolutions function.
|
inline |
This take an array of floats and modifies them in place to be between [-PI, PI].
| qs | A pointer to a float array |
| dof | The length of the float array |
| int tesseract_kinematics::inverse | ( | const Eigen::Isometry3d & | T, |
| const URParameters & | params, | ||
| double * | q_sols, | ||
| double | q6_des | ||
| ) |
|
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.
| jacobian | The jacobian to check if near a singularity |
| threshold | The threshold that all singular values must be greater than or equal to not be considered near a singularity |
|
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.
| qs | A pointer to a floats array |
| dof | The length of the float array |
| void tesseract_kinematics::KDLToEigen | ( | const KDL::Frame & | frame, |
| Eigen::Isometry3d & | transform | ||
| ) |
Convert KDL::Frame to Eigen::Isometry3d.
| frame | Input KDL Frame |
| transform | Output Eigen transform (Isometry3d) |
| 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.
| jacobian | Input KDL Jacobian |
| q_nrs | Input the columns to use |
| matrix | Output Eigen MatrixXd |
| void tesseract_kinematics::KDLToEigen | ( | const KDL::Jacobian & | jacobian, |
| Eigen::Ref< Eigen::MatrixXd > | matrix | ||
| ) |
Convert KDL::Jacobian to Eigen::Matrix.
| jacobian | Input KDL Jacobian |
| matrix | Output Eigen MatrixXd |
| void tesseract_kinematics::KDLToEigen | ( | const KDL::JntArray & | joints, |
| Eigen::Ref< Eigen::VectorXd > | vec | ||
| ) |
Convert KDL::JntArray to Eigen::Vector.
| joints | Input KDL joint array |
| vec | Output Eigen vector |
|
inlinestatic |
Numerically calculate a jacobian. This is mainly used for testing.
| jacobian | (Return) The jacobian which gets filled out. |
| kin | The kinematics object |
| joint_values | The joint values for which to calculate the jacobian |
| link_name | The link_name for which the jacobian should be calculated |
| link_point | The point on the link for which to calculate the jacobian |
|
inlinestatic |
Numerically calculate a jacobian. This is mainly used for testing.
| jacobian | (Return) The jacobian which gets filled out. |
| joint_group | The joint group object |
| joint_values | The joint values for which to calculate the jacobian |
| link_name | The link_name for which the jacobian should be calculated |
| link_point | The point on the link for which to calculate the jacobian |
| 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.
| results | KDL Chain data |
| scene_graph | The Scene Graph |
| base_name | The base link name of chain |
| tip_name | The tip link name of chain |
| 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.
| results | KDL Chain data |
| scene_graph | The Scene Graph |
| chains | A 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. |
|
inlinestatic |
Solve equation Ax=b for x Use this SVD to compute A+ (pseudoinverse of A). Weighting still TBD.
| A | Input matrix (represents Jacobian) |
| b | Input vector (represents desired pose) |
| x | Output vector (represents joint values) |
|
static |
The UR10e kinematic parameters.
|
static |
The UR10 kinematic parameters.
|
static |
The UR3e kinematic parameters.
|
static |
The UR3 kinematic parameters.
|
static |
The UR5e kinematic parameters.
|
static |
The UR5 kinematic parameters.
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |