rop_inv_kin.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_ROP_INVERSE_KINEMATICS_H
27 #define TESSERACT_KINEMATICS_ROP_INVERSE_KINEMATICS_H
28 
31 #include <memory>
32 #include <Eigen/Core>
34 
37 
38 namespace tesseract_kinematics
39 {
40 static const std::string DEFAULT_ROP_INV_KIN_SOLVER_NAME = "ROPInvKin";
41 class ForwardKinematics;
42 
47 {
48 public:
49  // LCOV_EXCL_START
50  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51  // LCOV_EXCL_STOP
52 
53  using Ptr = std::shared_ptr<ROPInvKin>;
54  using ConstPtr = std::shared_ptr<const ROPInvKin>;
55  using UPtr = std::unique_ptr<ROPInvKin>;
56  using ConstUPtr = std::unique_ptr<const ROPInvKin>;
57 
58  ~ROPInvKin() override = default;
59  ROPInvKin(const ROPInvKin& other);
60  ROPInvKin& operator=(const ROPInvKin& other);
61  ROPInvKin(ROPInvKin&&) = default;
62  ROPInvKin& operator=(ROPInvKin&&) = default;
63 
77  const tesseract_scene_graph::SceneState& scene_state,
78  InverseKinematics::UPtr manipulator,
79  double manipulator_reach,
80  std::unique_ptr<ForwardKinematics> positioner,
81  const Eigen::VectorXd& positioner_sample_resolution,
82  std::string solver_name = DEFAULT_ROP_INV_KIN_SOLVER_NAME);
83 
98  const tesseract_scene_graph::SceneState& scene_state,
99  InverseKinematics::UPtr manipulator,
100  double manipulator_reach,
101  std::unique_ptr<ForwardKinematics> positioner,
102  const Eigen::MatrixX2d& positioner_sample_range,
103  const Eigen::VectorXd& positioner_sample_resolution,
104  std::string solver_name = DEFAULT_ROP_INV_KIN_SOLVER_NAME);
105 
107  const Eigen::Ref<const Eigen::VectorXd>& seed) const override final;
108 
109  std::vector<std::string> getJointNames() const override final;
110  Eigen::Index numJoints() const override final;
111  std::string getBaseLinkName() const override final;
112  std::string getWorkingFrame() const override final;
113  std::vector<std::string> getTipLinkNames() const override final;
114  std::string getSolverName() const override final;
115  InverseKinematics::UPtr clone() const override final;
116 
117 private:
118  std::vector<std::string> joint_names_;
121  std::string manip_tip_link_;
122  std::string positioner_tip_link_;
123  double manip_reach_{ 0 };
124  Eigen::Index dof_{ -1 };
125  Eigen::Isometry3d positioner_to_robot_{ Eigen::Isometry3d::Identity() };
126  std::vector<Eigen::VectorXd> dof_range_;
129  void init(const tesseract_scene_graph::SceneGraph& scene_graph,
130  const tesseract_scene_graph::SceneState& scene_state,
131  InverseKinematics::UPtr manipulator,
132  double manipulator_reach,
133  std::unique_ptr<ForwardKinematics> positioner,
134  const Eigen::MatrixX2d& poitioner_sample_range,
135  const Eigen::VectorXd& positioner_sample_resolution,
136  std::string solver_name = DEFAULT_ROP_INV_KIN_SOLVER_NAME);
137 
140  const Eigen::Ref<const Eigen::VectorXd>& seed) const;
141 
142  void nested_ik(IKSolutions& solutions,
143  int loop_level,
144  const std::vector<Eigen::VectorXd>& dof_range,
145  const tesseract_common::TransformMap& tip_link_poses,
146  Eigen::VectorXd& positioner_pose,
147  const Eigen::Ref<const Eigen::VectorXd>& seed) const;
148 
149  void ikAt(IKSolutions& solutions,
150  const tesseract_common::TransformMap& tip_link_poses,
151  Eigen::VectorXd& positioner_pose,
152  const Eigen::Ref<const Eigen::VectorXd>& seed) const;
153 };
154 } // namespace tesseract_kinematics
155 #endif // TESSERACT_KINEMATICS_ROP_INVERSE_KINEMATICS_H
tesseract_kinematics::ROPInvKin::manip_inv_kin_
InverseKinematics::UPtr manip_inv_kin_
Definition: rop_inv_kin.h:119
tesseract_kinematics::ForwardKinematics
Forward kinematics functions.
Definition: forward_kinematics.h:43
tesseract_kinematics::ROPInvKin::manip_tip_link_
std::string manip_tip_link_
Definition: rop_inv_kin.h:121
tesseract_kinematics::DEFAULT_ROP_INV_KIN_SOLVER_NAME
static const std::string DEFAULT_ROP_INV_KIN_SOLVER_NAME
Definition: rop_inv_kin.h:40
tesseract_kinematics::ROPInvKin::positioner_tip_link_
std::string positioner_tip_link_
Definition: rop_inv_kin.h:122
tesseract_kinematics::ROPInvKin::dof_range_
std::vector< Eigen::VectorXd > dof_range_
Definition: rop_inv_kin.h:126
tesseract_kinematics::ROPInvKin::getSolverName
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: rop_inv_kin.cpp:256
tesseract_kinematics::ROPInvKin::calcInvKinHelper
IKSolutions calcInvKinHelper(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
calcFwdKin helper function
Definition: rop_inv_kin.cpp:178
tesseract_kinematics::ROPInvKin::getBaseLinkName
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: rop_inv_kin.cpp:250
tesseract_kinematics::ROPInvKin::manip_reach_
double manip_reach_
Definition: rop_inv_kin.h:123
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_kinematics::ROPInvKin::positioner_to_robot_
Eigen::Isometry3d positioner_to_robot_
Definition: rop_inv_kin.h:125
tesseract_kinematics::InverseKinematics::ConstUPtr
std::unique_ptr< const InverseKinematics > ConstUPtr
Definition: inverse_kinematics.h:53
tesseract_kinematics::InverseKinematics::ConstPtr
std::shared_ptr< const InverseKinematics > ConstPtr
Definition: inverse_kinematics.h:51
inverse_kinematics.h
Inverse kinematics functions.
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::SceneGraph
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
tesseract_scene_graph::SceneState
tesseract_kinematics::ROPInvKin::joint_names_
std::vector< std::string > joint_names_
Definition: rop_inv_kin.h:118
tesseract_kinematics::ROPInvKin::ikAt
void ikAt(IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
Definition: rop_inv_kin.cpp:207
tesseract_kinematics::ROPInvKin::clone
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: rop_inv_kin.cpp:160
tesseract_kinematics::ROPInvKin::numJoints
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: rop_inv_kin.cpp:248
tesseract_kinematics::ROPInvKin::dof_
Eigen::Index dof_
Definition: rop_inv_kin.h:124
tesseract_kinematics::ROPInvKin::~ROPInvKin
~ROPInvKin() override=default
tesseract_kinematics::ROPInvKin::getWorkingFrame
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Definition: rop_inv_kin.cpp:252
tesseract_kinematics::ROPInvKin::getTipLinkNames
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
Definition: rop_inv_kin.cpp:254
tesseract_kinematics::ROPInvKin::ROPInvKin
ROPInvKin(const ROPInvKin &other)
Definition: rop_inv_kin.cpp:162
tesseract_kinematics::ROPInvKin::solver_name_
std::string solver_name_
Name of this solver.
Definition: rop_inv_kin.h:127
tesseract_kinematics::ROPInvKin::nested_ik
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
Definition: rop_inv_kin.cpp:187
fwd.h
tesseract_kinematics::ROPInvKin::positioner_fwd_kin_
std::unique_ptr< ForwardKinematics > positioner_fwd_kin_
Definition: rop_inv_kin.h:120
tesseract_kinematics::InverseKinematics
Inverse kinematics functions.
Definition: inverse_kinematics.h:43
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_kinematics::InverseKinematics::Ptr
std::shared_ptr< InverseKinematics > Ptr
Definition: inverse_kinematics.h:50
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::ROPInvKin::getJointNames
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: rop_inv_kin.cpp:246
tesseract_kinematics::ROPInvKin::init
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)
Definition: rop_inv_kin.cpp:92
tesseract_kinematics::ROPInvKin::calcInvKin
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.
Definition: rop_inv_kin.cpp:237
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
macros.h
tesseract_kinematics::ROPInvKin
Robot on Positioner Inverse kinematic implementation.
Definition: rop_inv_kin.h:46
tesseract_kinematics::ROPInvKin::operator=
ROPInvKin & operator=(const ROPInvKin &other)
Definition: rop_inv_kin.cpp:164


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14