![]() |
Tesseract
Motion Planning Environment
|
Forward kinematics functions. More...
#include <forward_kinematics.h>

Public Types | |
| using | Ptr = std::shared_ptr< ForwardKinematics > |
| using | ConstPtr = std::shared_ptr< const ForwardKinematics > |
| using | UPtr = std::unique_ptr< ForwardKinematics > |
| using | ConstUPtr = std::unique_ptr< const ForwardKinematics > |
Public Member Functions | |
| ForwardKinematics ()=default | |
| virtual | ~ForwardKinematics ()=default |
| ForwardKinematics (const ForwardKinematics &)=default | |
| ForwardKinematics & | operator= (const ForwardKinematics &)=default |
| ForwardKinematics (ForwardKinematics &&)=default | |
| ForwardKinematics & | operator= (ForwardKinematics &&)=default |
| virtual tesseract_common::TransformMap | calcFwdKin (const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const =0 |
| Calculates the transform for each tip link in the kinematic group. More... | |
| virtual Eigen::MatrixXd | calcJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &link_name) const =0 |
| Calculates the Jacobian matrix for a given joint state in the reference frame of the specified link. More... | |
| virtual std::string | getBaseLinkName () const =0 |
| Get the robot base link name. More... | |
| virtual std::vector< std::string > | getJointNames () const =0 |
| Get list of joint names for kinematic object. More... | |
| virtual std::vector< std::string > | getTipLinkNames () const =0 |
| Get list of tip link names for kinematic object. More... | |
| virtual Eigen::Index | numJoints () const =0 |
| Number of joints in robot. More... | |
| virtual std::string | getSolverName () const =0 |
| Get the name of the solver. Recommend using the name of the class. More... | |
| virtual ForwardKinematics::UPtr | clone () const =0 |
| Clone the forward kinematics object. More... | |
Forward kinematics functions.
| using tesseract_kinematics::ForwardKinematics::ConstPtr = std::shared_ptr<const ForwardKinematics> |
| using tesseract_kinematics::ForwardKinematics::ConstUPtr = std::unique_ptr<const ForwardKinematics> |
| using tesseract_kinematics::ForwardKinematics::Ptr = std::shared_ptr<ForwardKinematics> |
| using tesseract_kinematics::ForwardKinematics::UPtr = std::unique_ptr<ForwardKinematics> |
|
default |
|
virtualdefault |
|
default |
|
default |
|
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)
| joint_angles | Vector of joint angles (size must match number of joints in robot chain) |
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
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)
| joint_angles | Input vector of joint angles |
| link_name | The link name to calculate jacobian |
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
pure virtual |
Clone the forward kinematics object.
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
pure virtual |
Get the robot base link name.
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
pure virtual |
Get list of joint names for kinematic object.
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
pure virtual |
Get the name of the solver. Recommend using the name of the class.
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
pure virtual |
Get list of tip link names for kinematic object.
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
pure virtual |
Number of joints in robot.
Implemented in tesseract_kinematics::KDLFwdKinChain.
|
default |
|
default |