Kinematics utility functions. More...
#include <tesseract_common/macros.h>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <console_bridge/console.h>
#include <tesseract_common/utils.h>
#include <tesseract_common/kinematic_limits.h>
Go to the source code of this file.
Classes | |
struct | tesseract_kinematics::Manipulability |
Contains both manipulability ellipsoid and force ellipsoid data. More... | |
struct | tesseract_kinematics::ManipulabilityEllipsoid |
Used to store Manipulability and Force Ellipsoid data. More... | |
Namespaces | |
tesseract_kinematics | |
Typedefs | |
template<typename FloatType > | |
using | tesseract_kinematics::VectorX = Eigen::Matrix< FloatType, Eigen::Dynamic, 1 > |
Functions | |
Manipulability | tesseract_kinematics::calcManipulability (const Eigen::Ref< const Eigen::MatrixXd > &jacobian) |
Calculate manipulability data about the provided jacobian. More... | |
bool | tesseract_kinematics::dampedPInv (const Eigen::Ref< const Eigen::MatrixXd > &A, Eigen::Ref< Eigen::MatrixXd > P, double eps=0.011, double lambda=0.01) |
Calculate Damped Pseudoinverse Use this SVD to compute A+ (pseudoinverse of A). Weighting still TBD. More... | |
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) |
Kinematics only return solution between PI and -PI. Provided the limits it will append redundant solutions. More... | |
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) |
This a recursive function for calculating all permutations of the redundant solutions. More... | |
template<typename FloatType > | |
void | tesseract_kinematics::harmonizeTowardMedian (Eigen::Ref< VectorX< FloatType >> qs, const std::vector< Eigen::Index > &redundancy_capable_joints, const Eigen::Ref< const Eigen::Matrix< FloatType, Eigen::Dynamic, 2 >> &position_limits) |
This takes the array of floats and modifies them in place to be between [-PI, PI] relative to limits median. More... | |
template<typename FloatType > | |
void | tesseract_kinematics::harmonizeTowardZero (Eigen::Ref< VectorX< FloatType >> qs, const std::vector< Eigen::Index > &redundancy_capable_joints) |
This takes an array of floats and modifies them in place to be between [-PI, PI]. More... | |
bool | tesseract_kinematics::isNearSingularity (const Eigen::Ref< const Eigen::MatrixXd > &jacobian, double threshold=0.01) |
Check if the provided jacobian is near a singularity. More... | |
template<typename FloatType > | |
bool | tesseract_kinematics::isValid (const std::array< FloatType, 6 > &qs) |
Given a vector of floats, this check if they are finite. More... | |
void | tesseract_kinematics::numericalJacobian (Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Isometry3d &change_base, 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... | |
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) |
Numerically calculate a jacobian. This is mainly used for testing. More... | |
bool | tesseract_kinematics::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... | |
Kinematics utility functions.
Definition in file utils.h.