26#ifndef TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
27#define TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
81 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
84 using Ptr = std::shared_ptr<IKFastInvKin>;
85 using ConstPtr = std::shared_ptr<const IKFastInvKin>;
86 using UPtr = std::unique_ptr<IKFastInvKin>;
87 using ConstUPtr = std::unique_ptr<const IKFastInvKin>;
105 std::vector<Eigen::Index> redundancy_capable_joints,
110 const Eigen::Ref<const Eigen::VectorXd>&
seed)
const override;
128 static std::vector<std::vector<double>>
IKFast Inverse Kinematics Implmentation.
Definition: ikfast_inv_kin.h:78
std::string getWorkingFrame() const override
Get the inverse kinematics working frame.
Definition: ikfast_inv_kin.hpp:156
std::vector< std::vector< double > > free_joint_states_
Definition: ikfast_inv_kin.h:139
std::vector< Eigen::Index > redundancy_capable_joints_
Definition: ikfast_inv_kin.h:135
static std::vector< std::vector< double > > generateAllFreeJointStateCombinations(const std::vector< std::vector< double > > &free_joint_samples)
Generates all possible combinations of joint states and stores it to the free_joint_states_ class mem...
Definition: ikfast_inv_kin.hpp:161
std::vector< std::string > joint_names_
Joint names for the kinematic object.
Definition: ikfast_inv_kin.h:134
Eigen::Index numJoints() const override
Number of joints in robot.
Definition: ikfast_inv_kin.hpp:153
std::string base_link_name_
Link name of first link in the kinematic object.
Definition: ikfast_inv_kin.h:132
IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override
Calculates joint solutions given a pose for each tip link.
Definition: ikfast_inv_kin.hpp:77
~IKFastInvKin() override=default
IKFastInvKin(IKFastInvKin &&)=default
IKFastInvKin & operator=(IKFastInvKin &&)=default
std::shared_ptr< IKFastInvKin > Ptr
Definition: ikfast_inv_kin.h:84
std::string solver_name_
Redundancy capable joints.
Definition: ikfast_inv_kin.h:136
std::vector< std::string > getJointNames() const override
Get list of joint names for kinematic object.
Definition: ikfast_inv_kin.hpp:154
std::shared_ptr< const IKFastInvKin > ConstPtr
Definition: ikfast_inv_kin.h:85
IKFastInvKin & operator=(const IKFastInvKin &other)
Definition: ikfast_inv_kin.hpp:65
std::string getBaseLinkName() const override
Get the robot base link name.
Definition: ikfast_inv_kin.hpp:155
std::unique_ptr< const IKFastInvKin > ConstUPtr
Definition: ikfast_inv_kin.h:87
InverseKinematics::UPtr clone() const override
Clone the forward kinematics object.
Definition: ikfast_inv_kin.hpp:61
std::vector< std::string > getTipLinkNames() const override
Get the names of the tip links of the kinematics group.
Definition: ikfast_inv_kin.hpp:157
std::string getSolverName() const override
Get the name of the solver. Recommend using the name of the class.
Definition: ikfast_inv_kin.hpp:158
std::unique_ptr< IKFastInvKin > UPtr
Definition: ikfast_inv_kin.h:86
std::string tip_link_name_
Link name of last kink in the kinematic object.
Definition: ikfast_inv_kin.h:133
Inverse kinematics functions.
Definition: inverse_kinematics.h:47
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:55
Eigen::VectorXd seed
Definition: ikfast_kinematics_7dof_unit.cpp:48
std::string base_link_name
Definition: ikfast_kinematics_7dof_unit.cpp:52
std::string tip_link_name
Definition: ikfast_kinematics_7dof_unit.cpp:53
std::vector< std::vector< double > > free_joint_states
Definition: ikfast_kinematics_7dof_unit.cpp:58
Inverse kinematics functions.
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
Definition: forward_kinematics.h:44
static const std::string IKFAST_INV_KIN_CHAIN_SOLVER_NAME
Definition: ikfast_inv_kin.h:34
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:41
joint_state joint_names
Definition: tesseract_common_serialization_unit.cpp:75