26#ifndef TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
27#define TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
34#include <Eigen/Geometry>
37#include <unordered_map>
50 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 using Ptr = std::shared_ptr<ForwardKinematics>;
54 using ConstPtr = std::shared_ptr<const ForwardKinematics>;
55 using UPtr = std::unique_ptr<ForwardKinematics>;
56 using ConstUPtr = std::unique_ptr<const ForwardKinematics>;
84 virtual Eigen::MatrixXd
calcJacobian(
const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
85 const std::string& link_name)
const = 0;
Forward kinematics functions.
Definition: forward_kinematics.h:47
std::shared_ptr< const ForwardKinematics > ConstPtr
Definition: forward_kinematics.h:54
virtual ~ForwardKinematics()=default
virtual std::vector< std::string > getTipLinkNames() const =0
Get list of tip link names for kinematic object.
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.
std::unique_ptr< ForwardKinematics > UPtr
Definition: forward_kinematics.h:55
std::unique_ptr< const ForwardKinematics > ConstUPtr
Definition: forward_kinematics.h:56
ForwardKinematics & operator=(ForwardKinematics &&)=default
ForwardKinematics(const 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.
virtual std::string getSolverName() const =0
Get the name of the solver. Recommend using the name of the class.
ForwardKinematics & operator=(const ForwardKinematics &)=default
ForwardKinematics(ForwardKinematics &&)=default
virtual std::string getBaseLinkName() const =0
Get the robot base link name.
std::shared_ptr< ForwardKinematics > Ptr
Definition: forward_kinematics.h:53
ForwardKinematics()=default
virtual ForwardKinematics::UPtr clone() const =0
Clone the forward kinematics object.
virtual std::vector< std::string > getJointNames() const =0
Get list of joint names for kinematic object.
virtual Eigen::Index numJoints() const =0
Number of joints in robot.
A basic scene graph using boost.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
Definition: forward_kinematics.h:44