inverse_kinematics.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_INVERSE_KINEMATICS_H
27 #define TESSERACT_KINEMATICS_INVERSE_KINEMATICS_H
28 
31 #include <vector>
32 #include <string>
33 #include <Eigen/Core>
34 #include <memory>
36 
39 
40 namespace tesseract_kinematics
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<InverseKinematics>;
51  using ConstPtr = std::shared_ptr<const InverseKinematics>;
52  using UPtr = std::unique_ptr<InverseKinematics>;
53  using ConstUPtr = std::unique_ptr<const InverseKinematics>;
54 
55  InverseKinematics() = default;
56  virtual ~InverseKinematics();
57  InverseKinematics(const InverseKinematics&) = default;
61 
75  virtual IKSolutions calcInvKin(const tesseract_common::TransformMap& tip_link_poses,
76  const Eigen::Ref<const Eigen::VectorXd>& seed) const = 0;
77 
82  virtual std::vector<std::string> getJointNames() const = 0;
83 
88  virtual Eigen::Index numJoints() const = 0;
89 
91  virtual std::string getBaseLinkName() const = 0;
92 
97  virtual std::string getWorkingFrame() const = 0;
98 
104  virtual std::vector<std::string> getTipLinkNames() const = 0;
105 
107  virtual std::string getSolverName() const = 0;
108 
110  virtual InverseKinematics::UPtr clone() const = 0;
111 };
112 
113 } // namespace tesseract_kinematics
114 #endif // TESSERACT_KINEMATICS_INVERSE_KINEMATICS_H
types.h
Kinematics types.
tesseract_kinematics::InverseKinematics::calcInvKin
virtual IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const =0
Calculates joint solutions given a pose for each tip link.
tesseract_kinematics::InverseKinematics::InverseKinematics
InverseKinematics()=default
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_kinematics::InverseKinematics::ConstUPtr
std::unique_ptr< const InverseKinematics > ConstUPtr
Definition: inverse_kinematics.h:53
tesseract_kinematics::InverseKinematics::ConstPtr
std::shared_ptr< const InverseKinematics > ConstPtr
Definition: inverse_kinematics.h:51
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_kinematics::InverseKinematics::clone
virtual InverseKinematics::UPtr clone() const =0
Clone the forward kinematics object.
tesseract_kinematics::InverseKinematics::getJointNames
virtual std::vector< std::string > getJointNames() const =0
Get list of joint names for kinematic object.
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
tesseract_kinematics::InverseKinematics::operator=
InverseKinematics & operator=(const InverseKinematics &)=default
tesseract_kinematics::InverseKinematics::getWorkingFrame
virtual std::string getWorkingFrame() const =0
Get the inverse kinematics working frame.
tesseract_kinematics::InverseKinematics::getBaseLinkName
virtual std::string getBaseLinkName() const =0
Get the robot base link name.
tesseract_kinematics::InverseKinematics::getSolverName
virtual std::string getSolverName() const =0
Get the name of the solver. Recommend using the name of the class.
tesseract_kinematics::InverseKinematics::~InverseKinematics
virtual ~InverseKinematics()
eigen_types.h
tesseract_kinematics::InverseKinematics
Inverse kinematics functions.
Definition: inverse_kinematics.h:43
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_kinematics::InverseKinematics::Ptr
std::shared_ptr< InverseKinematics > Ptr
Definition: inverse_kinematics.h:50
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::InverseKinematics::getTipLinkNames
virtual std::vector< std::string > getTipLinkNames() const =0
Get the names of the tip links of the kinematics group.
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
macros.h
tesseract_kinematics::InverseKinematics::numJoints
virtual Eigen::Index numJoints() const =0
Number of joints in robot.


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