Structure containing the data required to solve inverse kinematics. More...
#include <kinematic_group.h>
Public Member Functions | |
KinGroupIKInput ()=default | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | KinGroupIKInput (const Eigen::Isometry3d &p, std::string wf, std::string tl) |
Public Attributes | |
Eigen::Isometry3d | pose |
The desired inverse kinematic pose. More... | |
std::string | tip_link_name |
The tip link of the kinematic object to solve IK. More... | |
std::string | working_frame |
The link name the pose is relative to. More... | |
Structure containing the data required to solve inverse kinematics.
This structure provides the ability to specify IK targets for arbitrary tool links and defined with respect to arbitrary reference frames. Under the hood, the KinematicGroup class will transform these poses appropriately into the correct working frame required by the inverse kinematics solver. This improves the flexibility and ease-of-use of this class for performing IK
Definition at line 48 of file kinematic_group.h.
tesseract_kinematics::KinGroupIKInput::KinGroupIKInput | ( | const Eigen::Isometry3d & | p, |
std::string | wf, | ||
std::string | tl | ||
) |
Definition at line 101 of file kinematic_group.cpp.
|
default |
Eigen::Isometry3d tesseract_kinematics::KinGroupIKInput::pose |
The desired inverse kinematic pose.
Definition at line 59 of file kinematic_group.h.
std::string tesseract_kinematics::KinGroupIKInput::tip_link_name |
The tip link of the kinematic object to solve IK.
The provided tip link name must be listed in InverseKinematics::getTipLinkNames()
Definition at line 71 of file kinematic_group.h.
std::string tesseract_kinematics::KinGroupIKInput::working_frame |
The link name the pose is relative to.
The provided working frame must be listed in InverseKinematics::getWorkingFrames()
Definition at line 65 of file kinematic_group.h.