forward_kinematics.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
27 #define TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
28 
31 #include <vector>
32 #include <string>
33 #include <Eigen/Core>
34 #include <memory>
36 
39 
41 {
44 {
45 public:
46  // LCOV_EXCL_START
47  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
48  // LCOV_EXCL_STOP
49 
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>;
54 
55  ForwardKinematics() = default;
56  virtual ~ForwardKinematics() = default;
57  ForwardKinematics(const ForwardKinematics&) = default;
61 
70  virtual tesseract_common::TransformMap calcFwdKin(const Eigen::Ref<const Eigen::VectorXd>& joint_angles) const = 0;
71 
81  virtual Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
82  const std::string& link_name) const = 0;
83 
85  virtual std::string getBaseLinkName() const = 0;
86 
91  virtual std::vector<std::string> getJointNames() const = 0;
92 
97  virtual std::vector<std::string> getTipLinkNames() const = 0;
98 
103  virtual Eigen::Index numJoints() const = 0;
104 
106  virtual std::string getSolverName() const = 0;
107 
109  virtual ForwardKinematics::UPtr clone() const = 0;
110 };
111 } // namespace tesseract_kinematics
112 
113 #endif // TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
tesseract_kinematics::ForwardKinematics::getJointNames
virtual std::vector< std::string > getJointNames() const =0
Get list of joint names for kinematic object.
tesseract_kinematics::ForwardKinematics
Forward kinematics functions.
Definition: forward_kinematics.h:43
tesseract_kinematics::ForwardKinematics::getBaseLinkName
virtual std::string getBaseLinkName() const =0
Get the robot base link name.
tesseract_kinematics::ForwardKinematics::ConstPtr
std::shared_ptr< const ForwardKinematics > ConstPtr
Definition: forward_kinematics.h:51
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_kinematics::ForwardKinematics::numJoints
virtual Eigen::Index numJoints() const =0
Number of joints in robot.
tesseract_kinematics::ForwardKinematics::~ForwardKinematics
virtual ~ForwardKinematics()=default
tesseract_kinematics::ForwardKinematics::calcFwdKin
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.
tesseract_kinematics::ForwardKinematics::operator=
ForwardKinematics & operator=(const ForwardKinematics &)=default
tesseract_kinematics::ForwardKinematics::getSolverName
virtual std::string getSolverName() const =0
Get the name of the solver. Recommend using the name of the class.
fwd.h
tesseract_kinematics::ForwardKinematics::getTipLinkNames
virtual std::vector< std::string > getTipLinkNames() const =0
Get list of tip link names for kinematic object.
tesseract_kinematics::ForwardKinematics::ForwardKinematics
ForwardKinematics()=default
tesseract_kinematics::ForwardKinematics::calcJacobian
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.
eigen_types.h
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_kinematics::ForwardKinematics::ConstUPtr
std::unique_ptr< const ForwardKinematics > ConstUPtr
Definition: forward_kinematics.h:53
tesseract_kinematics::ForwardKinematics::UPtr
std::unique_ptr< ForwardKinematics > UPtr
Definition: forward_kinematics.h:52
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::ForwardKinematics::clone
virtual ForwardKinematics::UPtr clone() const =0
Clone the forward kinematics object.
tesseract_kinematics::ForwardKinematics::Ptr
std::shared_ptr< ForwardKinematics > Ptr
Definition: forward_kinematics.h:50
macros.h


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:12