Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_ROP_INVERSE_KINEMATICS_H
27 #define TESSERACT_KINEMATICS_ROP_INVERSE_KINEMATICS_H
50 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 using Ptr = std::shared_ptr<ROPInvKin>;
54 using ConstPtr = std::shared_ptr<const ROPInvKin>;
55 using UPtr = std::unique_ptr<ROPInvKin>;
79 double manipulator_reach,
80 std::unique_ptr<ForwardKinematics> positioner,
81 const Eigen::VectorXd& positioner_sample_resolution,
100 double manipulator_reach,
101 std::unique_ptr<ForwardKinematics> positioner,
102 const Eigen::MatrixX2d& positioner_sample_range,
103 const Eigen::VectorXd& positioner_sample_resolution,
107 const Eigen::Ref<const Eigen::VectorXd>& seed)
const override final;
109 std::vector<std::string>
getJointNames() const override final;
110 Eigen::Index
numJoints() const override final;
132 double manipulator_reach,
133 std::unique_ptr<ForwardKinematics> positioner,
134 const Eigen::MatrixX2d& poitioner_sample_range,
135 const Eigen::VectorXd& positioner_sample_resolution,
140 const Eigen::Ref<const Eigen::VectorXd>& seed)
const;
144 const std::vector<Eigen::VectorXd>& dof_range,
146 Eigen::VectorXd& positioner_pose,
147 const Eigen::Ref<const Eigen::VectorXd>& seed)
const;
151 Eigen::VectorXd& positioner_pose,
152 const Eigen::Ref<const Eigen::VectorXd>& seed)
const;
155 #endif // TESSERACT_KINEMATICS_ROP_INVERSE_KINEMATICS_H
InverseKinematics::UPtr manip_inv_kin_
Forward kinematics functions.
std::string manip_tip_link_
static const std::string DEFAULT_ROP_INV_KIN_SOLVER_NAME
std::string positioner_tip_link_
std::vector< Eigen::VectorXd > dof_range_
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
IKSolutions calcInvKinHelper(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
calcFwdKin helper function
std::string getBaseLinkName() const override final
Get the robot base link name.
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Eigen::Isometry3d positioner_to_robot_
std::unique_ptr< const InverseKinematics > ConstUPtr
std::shared_ptr< const InverseKinematics > ConstPtr
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
std::unique_ptr< InverseKinematics > UPtr
std::vector< std::string > joint_names_
void ikAt(IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Eigen::Index numJoints() const override final
Number of joints in robot.
~ROPInvKin() override=default
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
ROPInvKin(const ROPInvKin &other)
std::string solver_name_
Name of this solver.
void nested_ik(IKSolutions &solutions, int loop_level, const std::vector< Eigen::VectorXd > &dof_range, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
std::unique_ptr< ForwardKinematics > positioner_fwd_kin_
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
std::shared_ptr< InverseKinematics > Ptr
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
void init(const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::MatrixX2d &poitioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_ROP_INV_KIN_SOLVER_NAME)
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.
Robot on Positioner Inverse kinematic implementation.
ROPInvKin & operator=(const ROPInvKin &other)