Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
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 <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<ForwardKinematics>;
54 using ConstPtr = std::shared_ptr<const ForwardKinematics>;
55 using UPtr = std::unique_ptr<ForwardKinematics>;
56 using ConstUPtr = std::unique_ptr<const ForwardKinematics>;
57
58 ForwardKinematics() = default;
59 virtual ~ForwardKinematics() = default;
64
73 virtual tesseract_common::TransformMap calcFwdKin(const Eigen::Ref<const Eigen::VectorXd>& joint_angles) const = 0;
74
84 virtual Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
85 const std::string& link_name) const = 0;
86
88 virtual std::string getBaseLinkName() const = 0;
89
94 virtual std::vector<std::string> getJointNames() const = 0;
95
100 virtual std::vector<std::string> getTipLinkNames() const = 0;
101
106 virtual Eigen::Index numJoints() const = 0;
107
109 virtual std::string getSolverName() const = 0;
110
112 virtual ForwardKinematics::UPtr clone() const = 0;
113};
114} // namespace tesseract_kinematics
115
116#endif // TESSERACT_KINEMATICS_FORWARD_KINEMATICS_H
Forward kinematics functions.
Definition: forward_kinematics.h:47
std::shared_ptr< const ForwardKinematics > ConstPtr
Definition: forward_kinematics.h:54
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
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.
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
Common Tesseract Types.