Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_REP_INVERSE_KINEMATICS_H
27 #define TESSERACT_KINEMATICS_REP_INVERSE_KINEMATICS_H
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 using Ptr = std::shared_ptr<REPInvKin>;
57 using ConstPtr = std::shared_ptr<const REPInvKin>;
58 using UPtr = std::unique_ptr<REPInvKin>;
80 double manipulator_reach,
81 std::unique_ptr<ForwardKinematics> positioner,
82 const Eigen::VectorXd& positioner_sample_resolution,
99 double manipulator_reach,
100 std::unique_ptr<ForwardKinematics> positioner,
101 const Eigen::MatrixX2d& positioner_sample_range,
102 const Eigen::VectorXd& positioner_sample_resolution,
106 const Eigen::Ref<const Eigen::VectorXd>& seed)
const override final;
108 std::vector<std::string>
getJointNames() const override final;
109 Eigen::Index
numJoints() const override final;
131 double manipulator_reach,
132 std::unique_ptr<ForwardKinematics> positioner,
133 const Eigen::MatrixX2d& poitioner_sample_range,
134 const Eigen::VectorXd& positioner_sample_resolution,
139 const Eigen::Ref<const Eigen::VectorXd>& seed)
const;
143 const std::vector<Eigen::VectorXd>& dof_range,
145 Eigen::VectorXd& positioner_pose,
146 const Eigen::Ref<const Eigen::VectorXd>& seed)
const;
150 Eigen::VectorXd& positioner_pose,
151 const Eigen::Ref<const Eigen::VectorXd>& seed)
const;
154 #endif // TESSERACT_KINEMATICS_REP_INVERSE_KINEMATICS_H
~REPInvKin() override=default
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Forward kinematics functions.
std::string manip_tip_link_
std::string solver_name_
Name of this solver.
REPInvKin(const REPInvKin &other)
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
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.
InverseKinematics::UPtr manip_inv_kin_
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
std::unique_ptr< const InverseKinematics > ConstUPtr
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
std::shared_ptr< const InverseKinematics > ConstPtr
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
std::string getBaseLinkName() const override final
Get the robot base link name.
std::unique_ptr< InverseKinematics > UPtr
static const std::string DEFAULT_REP_INV_KIN_SOLVER_NAME
std::vector< Eigen::VectorXd > dof_range_
std::string working_frame_
std::unique_ptr< ForwardKinematics > positioner_fwd_kin_
Eigen::Index numJoints() const override final
Number of joints in robot.
void ikAt(IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
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_REP_INV_KIN_SOLVER_NAME)
REPInvKin & operator=(const REPInvKin &other)
std::shared_ptr< InverseKinematics > Ptr
Robot With External Positioner Inverse kinematic implementation.
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
std::vector< std::string > joint_names_
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Eigen::Isometry3d manip_base_to_positioner_base_
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
IKSolutions calcInvKinHelper(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
calcFwdKin helper function