Go to the documentation of this file.
38 #ifndef TESSERACT_KINEMATICS_UR_INV_KIN_H
39 #define TESSERACT_KINEMATICS_UR_INV_KIN_H
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 using Ptr = std::shared_ptr<URInvKin>;
57 using ConstPtr = std::shared_ptr<const URInvKin>;
58 using UPtr = std::unique_ptr<URInvKin>;
59 using ConstUPtr = std::unique_ptr<const URInvKin>;
76 std::string base_link_name,
77 std::string tip_link_name,
78 std::vector<std::string> joint_names,
82 const Eigen::Ref<const Eigen::VectorXd>& seed)
const override final;
84 Eigen::Index
numJoints() const override final;
101 #endif // TESSERACT_KINEMATICS_UR_INV_KIN_H
static const std::string UR_INV_KIN_CHAIN_SOLVER_NAME
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
URInvKin(const URInvKin &other)
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Inverse kinematics functions.
URInvKin & operator=(const URInvKin &other)
std::string getBaseLinkName() const override final
Get the robot base link name.
std::vector< std::string > joint_names_
Joint names for the kinematic object.
std::unique_ptr< InverseKinematics > UPtr
The Universal Robot kinematic parameters.
std::string solver_name_
Name of this solver.
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Eigen::Index numJoints() const override final
Number of joints in robot.
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
std::unique_ptr< const URInvKin > ConstUPtr
Inverse kinematics functions.
std::shared_ptr< const URInvKin > ConstPtr
~URInvKin() override=default
std::string base_link_name_
Link name of first link in the kinematic object.
std::string tip_link_name_
Link name of last kink in the kinematic object.
tesseract_kinematics::IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override final
Calculates joint solutions given a pose for each tip link.
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
std::unique_ptr< URInvKin > UPtr
std::shared_ptr< URInvKin > Ptr
URParameters params_
The UR Inverse kinematics parameters.