Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
27 #define TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
47 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 using Ptr = std::shared_ptr<ForwardKinematics>;
51 using ConstPtr = std::shared_ptr<const ForwardKinematics>;
52 using UPtr = std::unique_ptr<ForwardKinematics>;
53 using ConstUPtr = std::unique_ptr<const ForwardKinematics>;
81 virtual Eigen::MatrixXd
calcJacobian(
const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
82 const std::string& link_name)
const = 0;
103 virtual Eigen::Index
numJoints()
const = 0;
113 #endif // TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
virtual std::vector< std::string > getJointNames() const =0
Get list of joint names for kinematic object.
Forward kinematics functions.
virtual std::string getBaseLinkName() const =0
Get the robot base link name.
std::shared_ptr< const ForwardKinematics > ConstPtr
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
virtual Eigen::Index numJoints() const =0
Number of joints in robot.
virtual ~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.
ForwardKinematics & operator=(const ForwardKinematics &)=default
virtual std::string getSolverName() const =0
Get the name of the solver. Recommend using the name of the class.
virtual std::vector< std::string > getTipLinkNames() const =0
Get list of tip link names for kinematic object.
ForwardKinematics()=default
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.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
std::unique_ptr< const ForwardKinematics > ConstUPtr
std::unique_ptr< ForwardKinematics > UPtr
virtual ForwardKinematics::UPtr clone() const =0
Clone the forward kinematics object.
std::shared_ptr< ForwardKinematics > Ptr