Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
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 <Eigen/Geometry>
35#include <iostream>
36#include <memory>
37#include <unordered_map>
39
42
44{
47{
48public:
49 // LCOV_EXCL_START
50 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51 // LCOV_EXCL_STOP
52
53 using Ptr = std::shared_ptr<InverseKinematics>;
54 using ConstPtr = std::shared_ptr<const InverseKinematics>;
55 using UPtr = std::unique_ptr<InverseKinematics>;
56 using ConstUPtr = std::unique_ptr<const InverseKinematics>;
57
58 InverseKinematics() = default;
59 virtual ~InverseKinematics() = default;
64
79 const Eigen::Ref<const Eigen::VectorXd>& seed) const = 0;
80
85 virtual std::vector<std::string> getJointNames() const = 0;
86
91 virtual Eigen::Index numJoints() const = 0;
92
94 virtual std::string getBaseLinkName() const = 0;
95
100 virtual std::string getWorkingFrame() const = 0;
101
107 virtual std::vector<std::string> getTipLinkNames() const = 0;
108
110 virtual std::string getSolverName() const = 0;
111
113 virtual InverseKinematics::UPtr clone() const = 0;
114};
115
116} // namespace tesseract_kinematics
117#endif // TESSERACT_KINEMATICS_INVERSE_KINEMATICS_H
Inverse kinematics functions.
Definition: inverse_kinematics.h:47
std::shared_ptr< InverseKinematics > Ptr
Definition: inverse_kinematics.h:53
InverseKinematics & operator=(const InverseKinematics &)=default
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.
InverseKinematics(const InverseKinematics &)=default
std::unique_ptr< const InverseKinematics > ConstUPtr
Definition: inverse_kinematics.h:56
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:55
virtual InverseKinematics::UPtr clone() const =0
Clone the forward kinematics object.
virtual std::string getBaseLinkName() const =0
Get the robot base link name.
virtual std::vector< std::string > getTipLinkNames() const =0
Get the names of the tip links of the kinematics group.
virtual Eigen::Index numJoints() const =0
Number of joints in robot.
InverseKinematics(InverseKinematics &&)=default
InverseKinematics & operator=(InverseKinematics &&)=default
std::shared_ptr< const InverseKinematics > ConstPtr
Definition: inverse_kinematics.h:54
virtual std::vector< std::string > getJointNames() const =0
Get list of joint names for kinematic object.
virtual std::string getWorkingFrame() const =0
Get the inverse kinematics working frame.
virtual std::string getSolverName() const =0
Get the name of the solver. Recommend using the name of the class.
Eigen::VectorXd seed
Definition: ikfast_kinematics_7dof_unit.cpp:48
Common Tesseract Macros.
#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
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:41
Common Tesseract Types.
Kinematics types.