Forward kinematics functions.
More...
#include <forward_kinematics.h>
Forward kinematics functions.
Definition at line 43 of file forward_kinematics.h.
◆ ConstPtr
◆ ConstUPtr
◆ Ptr
◆ UPtr
◆ ForwardKinematics() [1/3]
tesseract_kinematics::ForwardKinematics::ForwardKinematics |
( |
| ) |
|
|
default |
◆ ~ForwardKinematics()
virtual tesseract_kinematics::ForwardKinematics::~ForwardKinematics |
( |
| ) |
|
|
virtualdefault |
◆ ForwardKinematics() [2/3]
tesseract_kinematics::ForwardKinematics::ForwardKinematics |
( |
const ForwardKinematics & |
| ) |
|
|
default |
◆ ForwardKinematics() [3/3]
◆ calcFwdKin()
virtual tesseract_common::TransformMap tesseract_kinematics::ForwardKinematics::calcFwdKin |
( |
const Eigen::Ref< const Eigen::VectorXd > & |
joint_angles | ) |
const |
|
pure virtual |
Calculates the transform for each tip link in the kinematic group.
This should return a transform for every link listed in getTipLinkNames() Throws an exception on failures (including uninitialized)
- Parameters
-
joint_angles | Vector of joint angles (size must match number of joints in robot chain) |
- Returns
- A map of tip link names and transforms
Implemented in tesseract_kinematics::KDLFwdKinChain.
◆ calcJacobian()
virtual Eigen::MatrixXd tesseract_kinematics::ForwardKinematics::calcJacobian |
( |
const Eigen::Ref< const Eigen::VectorXd > & |
joint_angles, |
|
|
const std::string & |
link_name |
|
) |
| const |
|
pure virtual |
Calculates the Jacobian matrix for a given joint state in the reference frame of the specified link.
This should be able to return a jacobian given any link listed in getTipLinkNames() Throws an exception on failures (including uninitialized)
- Parameters
-
joint_angles | Input vector of joint angles |
link_name | The link name to calculate jacobian |
- Returns
- The jacobian at the provided link
Implemented in tesseract_kinematics::KDLFwdKinChain.
◆ clone()
◆ getBaseLinkName()
virtual std::string tesseract_kinematics::ForwardKinematics::getBaseLinkName |
( |
| ) |
const |
|
pure virtual |
◆ getJointNames()
virtual std::vector<std::string> tesseract_kinematics::ForwardKinematics::getJointNames |
( |
| ) |
const |
|
pure virtual |
◆ getSolverName()
virtual std::string tesseract_kinematics::ForwardKinematics::getSolverName |
( |
| ) |
const |
|
pure virtual |
◆ getTipLinkNames()
virtual std::vector<std::string> tesseract_kinematics::ForwardKinematics::getTipLinkNames |
( |
| ) |
const |
|
pure virtual |
◆ numJoints()
virtual Eigen::Index tesseract_kinematics::ForwardKinematics::numJoints |
( |
| ) |
const |
|
pure virtual |
◆ operator=() [1/2]
◆ operator=() [2/2]
The documentation for this class was generated from the following file: