Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
rep_inv_kin.h
Go to the documentation of this file.
1
26#ifndef TESSERACT_KINEMATICS_REP_INVERSE_KINEMATICS_H
27#define TESSERACT_KINEMATICS_REP_INVERSE_KINEMATICS_H
30#include <unordered_map>
31#include <console_bridge/console.h>
32
36
40
42{
43static const std::string DEFAULT_REP_INV_KIN_SOLVER_NAME = "REPInvKin";
44
52{
53public:
54 // LCOV_EXCL_START
55 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 // LCOV_EXCL_STOP
57
58 using Ptr = std::shared_ptr<REPInvKin>;
59 using ConstPtr = std::shared_ptr<const REPInvKin>;
60 using UPtr = std::unique_ptr<REPInvKin>;
61 using ConstUPtr = std::unique_ptr<const REPInvKin>;
62
63 ~REPInvKin() override = default;
64 REPInvKin(const REPInvKin& other);
65 REPInvKin& operator=(const REPInvKin& other);
66 REPInvKin(REPInvKin&&) = default;
68
81 InverseKinematics::UPtr manipulator,
82 double manipulator_reach,
83 ForwardKinematics::UPtr positioner,
84 const Eigen::VectorXd& positioner_sample_resolution,
85 std::string solver_name = DEFAULT_REP_INV_KIN_SOLVER_NAME);
86
100 InverseKinematics::UPtr manipulator,
101 double manipulator_reach,
102 ForwardKinematics::UPtr positioner,
103 const Eigen::MatrixX2d& positioner_sample_range,
104 const Eigen::VectorXd& positioner_sample_resolution,
105 std::string solver_name = DEFAULT_REP_INV_KIN_SOLVER_NAME);
106
108 const Eigen::Ref<const Eigen::VectorXd>& seed) const override final;
109
110 std::vector<std::string> getJointNames() const override final;
111 Eigen::Index numJoints() const override final;
112 std::string getBaseLinkName() const override final;
113 std::string getWorkingFrame() const override final;
114 std::vector<std::string> getTipLinkNames() const override final;
115 std::string getSolverName() const override final;
116 InverseKinematics::UPtr clone() const override final;
117
118private:
119 std::vector<std::string> joint_names_;
122 std::string working_frame_;
123 std::string manip_tip_link_;
124 double manip_reach_{ 0 };
126 Eigen::Index dof_{ -1 };
127 std::vector<Eigen::VectorXd> dof_range_;
132 InverseKinematics::UPtr manipulator,
133 double manipulator_reach,
134 ForwardKinematics::UPtr positioner,
135 const Eigen::MatrixX2d& poitioner_sample_range,
136 const Eigen::VectorXd& positioner_sample_resolution,
137 std::string solver_name = DEFAULT_REP_INV_KIN_SOLVER_NAME);
138
141 const Eigen::Ref<const Eigen::VectorXd>& seed) const;
142
143 void nested_ik(IKSolutions& solutions,
144 int loop_level,
145 const std::vector<Eigen::VectorXd>& dof_range,
146 const tesseract_common::TransformMap& tip_link_poses,
147 Eigen::VectorXd& positioner_pose,
148 const Eigen::Ref<const Eigen::VectorXd>& seed) const;
149
150 void ikAt(IKSolutions& solutions,
151 const tesseract_common::TransformMap& tip_link_poses,
152 Eigen::VectorXd& positioner_pose,
153 const Eigen::Ref<const Eigen::VectorXd>& seed) const;
154};
155} // namespace tesseract_kinematics
156#endif // TESSERACT_KINEMATICS_REP_INVERSE_KINEMATICS_H
#define vector(a, b, c)
Definition: FloatMath.inl:3227
Forward kinematics functions.
Definition: forward_kinematics.h:47
std::unique_ptr< ForwardKinematics > UPtr
Definition: forward_kinematics.h:55
Inverse kinematics functions.
Definition: inverse_kinematics.h:47
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:55
Robot With External Positioner Inverse kinematic implementation.
Definition: rep_inv_kin.h:52
std::string manip_tip_link_
Definition: rep_inv_kin.h:123
double manip_reach_
Definition: rep_inv_kin.h:124
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: rep_inv_kin.cpp:184
std::unique_ptr< const REPInvKin > ConstUPtr
Definition: rep_inv_kin.h:61
std::string working_frame_
Definition: rep_inv_kin.h:122
std::vector< Eigen::VectorXd > dof_range_
Definition: rep_inv_kin.h:127
Eigen::Index dof_
Definition: rep_inv_kin.h:126
InverseKinematics::UPtr manip_inv_kin_
Definition: rep_inv_kin.h:120
REPInvKin(REPInvKin &&)=default
IKSolutions calcInvKinHelper(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
calcFwdKin helper function
Definition: rep_inv_kin.cpp:175
std::unique_ptr< REPInvKin > UPtr
Definition: rep_inv_kin.h:60
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: rep_inv_kin.cpp:247
ForwardKinematics::UPtr positioner_fwd_kin_
Definition: rep_inv_kin.h:121
std::shared_ptr< const REPInvKin > ConstPtr
Definition: rep_inv_kin.h:59
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: rep_inv_kin.cpp:156
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: rep_inv_kin.cpp:249
Eigen::Isometry3d manip_base_to_positioner_base_
Definition: rep_inv_kin.h:125
std::shared_ptr< REPInvKin > Ptr
Definition: rep_inv_kin.h:58
REPInvKin & operator=(REPInvKin &&)=default
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: rep_inv_kin.cpp:245
std::vector< std::string > joint_names_
Definition: rep_inv_kin.h:119
std::string solver_name_
Name of this solver.
Definition: rep_inv_kin.h:128
void init(const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, ForwardKinematics::UPtr positioner, const Eigen::MatrixX2d &poitioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_REP_INV_KIN_SOLVER_NAME)
Definition: rep_inv_kin.cpp:92
REPInvKin & operator=(const REPInvKin &other)
Definition: rep_inv_kin.cpp:160
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
Definition: rep_inv_kin.cpp:253
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: rep_inv_kin.cpp:235
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Definition: rep_inv_kin.cpp:251
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: rep_inv_kin.cpp:255
~REPInvKin() override=default
void ikAt(IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
Definition: rep_inv_kin.cpp:204
Definition: graph.h:125
Forward kinematics functions.
A basic scene graph using boost.
Eigen::VectorXd seed
Definition: ikfast_kinematics_7dof_unit.cpp:48
auto scene_graph
Definition: ikfast_kinematics_7dof_unit.cpp:51
Inverse kinematics functions.
tesseract_scene_graph::SceneState scene_state
Definition: kinematics_factory_unit.cpp:265
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
Definition: forward_kinematics.h:44
static const std::string DEFAULT_REP_INV_KIN_SOLVER_NAME
Definition: rep_inv_kin.h:43
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:41
This holds a state of the scene.
This holds a state of the scene.
Definition: scene_state.h:54
Kinematics types.