Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_KINEMATIC_GROUP_H
27 #define TESSERACT_KINEMATICS_KINEMATIC_GROUP_H
32 #include <Eigen/Geometry>
40 class InverseKinematics;
51 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 KinGroupIKInput(
const Eigen::Isometry3d& p, std::string wf, std::string tl);
79 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 using Ptr = std::shared_ptr<KinematicGroup>;
83 using ConstPtr = std::shared_ptr<const KinematicGroup>;
84 using UPtr = std::unique_ptr<KinematicGroup>;
85 using ConstUPtr = std::unique_ptr<const KinematicGroup>;
101 std::vector<std::string> joint_names,
102 std::unique_ptr<InverseKinematics> inv_kin,
164 #endif // TESSERACT_KINEMATICS_KINEMATIC_GROUP_H
~KinematicGroup() override
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
A Joint Group is defined by a list of joint_names.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
std::unique_ptr< JointGroup > UPtr
A joint group with forward kinematics, Jacobian, limits methods.
tesseract_common::AlignedVector< KinGroupIKInput > KinGroupIKInputs
std::vector< std::string > joint_names_
std::vector< std::string > getAllPossibleTipLinkNames() const
Get the tip link name.
std::vector< std::string > working_frames_
IKSolutions calcInvKin(const KinGroupIKInputs &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
Calculates joint solutions given a pose.
KinematicGroup(const KinematicGroup &other)
Eigen::Isometry3d inv_to_fwd_base_
std::unique_ptr< const JointGroup > ConstUPtr
std::vector< Eigen::Index > inv_kin_joint_map_
std::shared_ptr< JointGroup > Ptr
std::vector< std::string > getAllValidWorkingFrames() const
Returns all possible working frames in which goal poses can be defined.
std::unique_ptr< InverseKinematics > inv_kin_
const InverseKinematics & getInverseKinematics() const
Get the inverse kinematics sovler.
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
std::shared_ptr< const JointGroup > ConstPtr
std::unordered_map< std::string, std::string > inv_tip_links_map_
KinematicGroup & operator=(const KinematicGroup &other)
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.