kinematic_group.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_KINEMATIC_GROUP_H
27 #define TESSERACT_KINEMATICS_KINEMATIC_GROUP_H
28 
31 #include <memory>
32 #include <Eigen/Geometry>
34 
37 
38 namespace tesseract_kinematics
39 {
40 class InverseKinematics;
49 {
50  // LCOV_EXCL_START
51  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
52  // LCOV_EXCL_STOP
53 
54  KinGroupIKInput(const Eigen::Isometry3d& p, std::string wf, std::string tl);
55 
56  KinGroupIKInput() = default;
57 
59  Eigen::Isometry3d pose;
60 
65  std::string working_frame;
66 
71  std::string tip_link_name; // This defines the internal kinematic group the information belongs to
72 };
74 
75 class KinematicGroup : public JointGroup
76 {
77 public:
78  // LCOV_EXCL_START
79  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80  // LCOV_EXCL_STOP
81 
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>;
86 
87  ~KinematicGroup() override;
88  KinematicGroup(const KinematicGroup& other);
90  KinematicGroup(KinematicGroup&&) = default;
92 
100  KinematicGroup(std::string name,
101  std::vector<std::string> joint_names,
102  std::unique_ptr<InverseKinematics> inv_kin,
103  const tesseract_scene_graph::SceneGraph& scene_graph,
104  const tesseract_scene_graph::SceneState& scene_state);
105 
114  IKSolutions calcInvKin(const KinGroupIKInputs& tip_link_poses, const Eigen::Ref<const Eigen::VectorXd>& seed) const;
115 
124  IKSolutions calcInvKin(const KinGroupIKInput& tip_link_pose, const Eigen::Ref<const Eigen::VectorXd>& seed) const;
125 
134  std::vector<std::string> getAllValidWorkingFrames() const;
135 
144  std::vector<std::string> getAllPossibleTipLinkNames() const;
145 
151 
152 private:
153  std::vector<std::string> joint_names_;
154  bool reorder_required_{ false };
155  std::vector<Eigen::Index> inv_kin_joint_map_;
156  std::unique_ptr<InverseKinematics> inv_kin_;
157  Eigen::Isometry3d inv_to_fwd_base_{ Eigen::Isometry3d::Identity() };
158  std::vector<std::string> working_frames_;
159  std::unordered_map<std::string, std::string> inv_tip_links_map_;
160 };
161 
162 } // namespace tesseract_kinematics
163 
164 #endif // TESSERACT_KINEMATICS_KINEMATIC_GROUP_H
tesseract_kinematics::KinGroupIKInput::KinGroupIKInput
KinGroupIKInput()=default
tesseract_kinematics::KinGroupIKInput
Structure containing the data required to solve inverse kinematics.
Definition: kinematic_group.h:48
types.h
Kinematics types.
tesseract_kinematics::KinematicGroup::~KinematicGroup
~KinematicGroup() override
tesseract_common::AlignedVector
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
tesseract_kinematics::KinGroupIKInput::working_frame
std::string working_frame
The link name the pose is relative to.
Definition: kinematic_group.h:65
tesseract_kinematics::JointGroup
A Joint Group is defined by a list of joint_names.
Definition: joint_group.h:44
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_kinematics::JointGroup::UPtr
std::unique_ptr< JointGroup > UPtr
Definition: joint_group.h:53
joint_group.h
A joint group with forward kinematics, Jacobian, limits methods.
tesseract_scene_graph::SceneGraph
tesseract_kinematics::KinGroupIKInputs
tesseract_common::AlignedVector< KinGroupIKInput > KinGroupIKInputs
Definition: kinematic_group.h:73
tesseract_scene_graph::SceneState
tesseract_kinematics::KinematicGroup::joint_names_
std::vector< std::string > joint_names_
Definition: kinematic_group.h:153
tesseract_kinematics::KinematicGroup::getAllPossibleTipLinkNames
std::vector< std::string > getAllPossibleTipLinkNames() const
Get the tip link name.
Definition: kinematic_group.cpp:309
tesseract_kinematics::KinematicGroup::working_frames_
std::vector< std::string > working_frames_
Definition: kinematic_group.h:158
tesseract_kinematics::KinematicGroup::calcInvKin
IKSolutions calcInvKin(const KinGroupIKInputs &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
Calculates joint solutions given a pose.
Definition: kinematic_group.cpp:210
tesseract_kinematics::KinematicGroup::KinematicGroup
KinematicGroup(const KinematicGroup &other)
Definition: kinematic_group.cpp:193
tesseract_kinematics::KinGroupIKInput::pose
Eigen::Isometry3d pose
The desired inverse kinematic pose.
Definition: kinematic_group.h:59
tesseract_kinematics::KinematicGroup::inv_to_fwd_base_
Eigen::Isometry3d inv_to_fwd_base_
Definition: kinematic_group.h:157
tesseract_kinematics::JointGroup::ConstUPtr
std::unique_ptr< const JointGroup > ConstUPtr
Definition: joint_group.h:54
tesseract_kinematics::KinematicGroup::inv_kin_joint_map_
std::vector< Eigen::Index > inv_kin_joint_map_
Definition: kinematic_group.h:155
tesseract_kinematics::JointGroup::Ptr
std::shared_ptr< JointGroup > Ptr
Definition: joint_group.h:51
tesseract_kinematics::KinematicGroup::getAllValidWorkingFrames
std::vector< std::string > getAllValidWorkingFrames() const
Returns all possible working frames in which goal poses can be defined.
Definition: kinematic_group.cpp:307
tesseract_kinematics::KinematicGroup::inv_kin_
std::unique_ptr< InverseKinematics > inv_kin_
Definition: kinematic_group.h:156
tesseract_kinematics::KinematicGroup::getInverseKinematics
const InverseKinematics & getInverseKinematics() const
Get the inverse kinematics sovler.
Definition: kinematic_group.cpp:319
tesseract_kinematics::InverseKinematics
Inverse kinematics functions.
Definition: inverse_kinematics.h:43
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_kinematics::KinGroupIKInput::tip_link_name
std::string tip_link_name
The tip link of the kinematic object to solve IK.
Definition: kinematic_group.h:71
tesseract_kinematics::JointGroup::ConstPtr
std::shared_ptr< const JointGroup > ConstPtr
Definition: joint_group.h:52
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::KinematicGroup::inv_tip_links_map_
std::unordered_map< std::string, std::string > inv_tip_links_map_
Definition: kinematic_group.h:159
tesseract_kinematics::KinematicGroup::operator=
KinematicGroup & operator=(const KinematicGroup &other)
Definition: kinematic_group.cpp:197
tesseract_kinematics::KinematicGroup::reorder_required_
bool reorder_required_
Definition: kinematic_group.h:154
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
macros.h
tesseract_kinematics::KinematicGroup
Definition: kinematic_group.h:75


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