Tesseract 0.28.4
Loading...
Searching...
No Matches
utils.cpp File Reference

Kinematics utility functions. More...

Functions

void tesseract::kinematics::numericalJacobian (Eigen::Ref< Eigen::MatrixXd > jacobian, const Eigen::Isometry3d &change_base, const 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.
 
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.
 
void tesseract::kinematics::numericalJacobian (Eigen::Ref< Eigen::MatrixXd > jacobian, const JointGroup &joint_group, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &base_link_name, const Eigen::Isometry3d &base_link_offset, const std::string &link_name, const Eigen::Isometry3d &link_offset)
 Numerically calculate a jacobian when both source and target are active links.
 
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.
 
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.
 
bool tesseract::kinematics::isNearSingularity (const Eigen::Ref< const Eigen::MatrixXd > &jacobian, double threshold=0.01)
 Check if the provided jacobian is near a singularity.
 
Manipulability tesseract::kinematics::calcManipulability (const Eigen::Ref< const Eigen::MatrixXd > &jacobian)
 Calculate manipulability data about the provided jacobian.
 

Detailed Description

Kinematics utility functions.

Author
Levi Armstrong
Date
April 15, 2018
License
Software License Agreement (Apache License)
Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Function Documentation

◆ numericalJacobian() [1/3]

void tesseract::kinematics::numericalJacobian ( Eigen::Ref< Eigen::MatrixXd >  jacobian,
const Eigen::Isometry3d &  change_base,
const 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.

Parameters
jacobian(Return) The jacobian which gets filled out.
change_baseThe transform from the desired frame to the current base frame of the jacobian
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/3]

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.

Parameters
jacobian(Return) The jacobian which gets filled out.
change_baseThe transform from the desired frame to the current base frame of the jacobian
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

◆ numericalJacobian() [3/3]

void tesseract::kinematics::numericalJacobian ( Eigen::Ref< Eigen::MatrixXd >  jacobian,
const JointGroup joint_group,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const std::string &  base_link_name,
const Eigen::Isometry3d &  base_link_offset,
const std::string &  link_name,
const Eigen::Isometry3d &  link_offset 
)

Numerically calculate a jacobian when both source and target are active links.

Parameters
jacobian(Return) The jacobian which gets filled out.
joint_groupThe joint group object
joint_valuesThe joint values for which to calculate the jacobian
base_link_nameThe link name for which the jacobian is calculated in
base_link_offsetThe offset on the base link for which to calculate the jacobian in
link_nameThe link name for which the jacobian is calculated for
link_offsetThe offset on the link for which the jacobian is calcualted for

◆ solvePInv()

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.

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

◆ dampedPInv()

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.

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

◆ isNearSingularity()

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

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

◆ calcManipulability()

Manipulability tesseract::kinematics::calcManipulability ( const Eigen::Ref< const Eigen::MatrixXd > &  jacobian)

Calculate manipulability data about the provided jacobian.

Parameters
jacobianThe jacobian used to calculate manipulability
Returns
The manipulability data