ikfast_inv_kin.hpp
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_IMPL_IKFAST_INV_KIN_HPP
27 #define TESSERACT_KINEMATICS_IMPL_IKFAST_INV_KIN_HPP
28 
31 #include <stdexcept>
32 #include <console_bridge/console.h>
35 
38 
39 namespace tesseract_kinematics
40 {
41 inline IKFastInvKin::IKFastInvKin(std::string base_link_name,
42  std::string tip_link_name,
43  std::vector<std::string> joint_names,
44  std::string solver_name,
45  std::vector<std::vector<double>> free_joint_states)
46  : base_link_name_(std::move(base_link_name))
47  , tip_link_name_(std::move(tip_link_name))
48  , joint_names_(std::move(joint_names))
49  , solver_name_(std::move(solver_name))
50  , free_joint_states_(std::move(free_joint_states))
51 {
52 }
53 
54 inline InverseKinematics::UPtr IKFastInvKin::clone() const { return std::make_unique<IKFastInvKin>(*this); }
55 
56 inline IKFastInvKin::IKFastInvKin(const IKFastInvKin& other) { *this = other; }
57 
59 {
62  joint_names_ = other.joint_names_;
63  solver_name_ = other.solver_name_;
65 
66  return *this;
67 }
68 
70  const Eigen::Ref<const Eigen::VectorXd>& /*seed*/) const
71 {
72  assert(tip_link_poses.size() == 1);
73  assert(tip_link_poses.find(tip_link_name_) != tip_link_poses.end());
74  assert(std::abs(1.0 - tip_link_poses.at(tip_link_name_).matrix().determinant()) < 1e-6);
75 
76  const Eigen::Isometry3d& pose = tip_link_poses.at(tip_link_name_);
77 
78  // Convert to ikfast data type
79  Eigen::Transform<IkReal, 3, Eigen::Isometry> ikfast_tcp = pose.cast<IkReal>();
80 
81  // Decompose
82  const Eigen::Matrix<IkReal, 3, 1> translation = ikfast_tcp.translation();
83 
84  // Note the row major ordering here: IkFast expects the matrix in r00, r01, r02, ..., r11, r12, r13
85  // ordering
86  const Eigen::Matrix<IkReal, 3, 3, Eigen::RowMajor> rotation = ikfast_tcp.rotation();
87 
88  auto ikfast_dof = static_cast<std::size_t>(numJoints());
89 
90  // Call IK (TODO: Make a better solution list class? One that uses vector instead of list)
91  ikfast::IkSolutionList<IkReal> ikfast_solution_set;
92  std::vector<double> sols;
93 
94  // Lambda to add all possible solutions for a given combination of free joints, or nullptr if no free joints
95  auto addSols = [&](const double* pfree) {
96  ComputeIk(translation.data(), rotation.data(), pfree, ikfast_solution_set);
97 
98  // Unpack the solutions into the output vector
99  const auto n_sols = ikfast_solution_set.GetNumSolutions();
100 
101  std::vector<IkReal> ikfast_output;
102  ikfast_output.resize(n_sols * ikfast_dof);
103 
104  for (std::size_t i = 0; i < n_sols; ++i)
105  {
106  // This actually walks the list EVERY time from the start of i.
107  const auto& sol = ikfast_solution_set.GetSolution(i);
108  auto* out = ikfast_output.data() + i * ikfast_dof;
109  sol.GetSolution(out, pfree);
110  }
111 
112  sols.insert(
113  end(sols), std::make_move_iterator(ikfast_output.begin()), std::make_move_iterator(ikfast_output.end()));
114  };
115 
116  if (!free_joint_states_.empty())
117  {
118  for (auto j_combo : free_joint_states_)
119  {
120  addSols(j_combo.data());
121  }
122  }
123  else
124  {
125  addSols(nullptr);
126  }
127 
128  // Check the output
129  std::size_t num_sol = sols.size() / ikfast_dof;
130  IKSolutions solution_set;
131  solution_set.reserve(sols.size());
132  for (std::size_t i = 0; i < num_sol; i++)
133  {
134  Eigen::Map<Eigen::VectorXd> eigen_sol(sols.data() + ikfast_dof * i, static_cast<Eigen::Index>(ikfast_dof));
135  if (eigen_sol.array().allFinite())
136  solution_set.push_back(eigen_sol);
137  }
138 
139  return solution_set;
140 }
141 
142 inline Eigen::Index IKFastInvKin::numJoints() const { return static_cast<Eigen::Index>(GetNumJoints()); }
143 inline std::vector<std::string> IKFastInvKin::getJointNames() const { return joint_names_; }
144 inline std::string IKFastInvKin::getBaseLinkName() const { return base_link_name_; }
145 inline std::string IKFastInvKin::getWorkingFrame() const { return base_link_name_; }
146 inline std::vector<std::string> IKFastInvKin::getTipLinkNames() const { return { tip_link_name_ }; }
147 inline std::string IKFastInvKin::getSolverName() const { return solver_name_; }
148 
149 inline std::vector<std::vector<double>>
150 IKFastInvKin::generateAllFreeJointStateCombinations(const std::vector<std::vector<double>>& free_joint_samples)
151 {
152  std::vector<std::vector<double>> free_joint_states;
153  std::vector<std::size_t> curr_joint_indices(free_joint_samples.size(), 0);
154  while (curr_joint_indices.front() < free_joint_samples.front().size())
155  {
156  std::vector<double> curr_joint_values;
157  for (std::size_t i = 0; i < curr_joint_indices.size(); ++i)
158  curr_joint_values.push_back(free_joint_samples[i][curr_joint_indices[i]]);
159  free_joint_states.push_back(curr_joint_values);
160  curr_joint_indices.back()++;
161  for (std::size_t i = curr_joint_indices.size() - 1; i > 0; --i)
162  {
163  if (curr_joint_indices[i] == free_joint_samples[i].size())
164  {
165  curr_joint_indices[i] = 0;
166  curr_joint_indices[i - 1]++;
167  }
168  }
169  }
170  return free_joint_states;
171 }
172 
173 } // namespace tesseract_kinematics
174 
175 #endif // TESSERACT_KINEMATICS_IMPL_IKFAST_INV_KIN_HPP
GetNumJoints
IKFAST_API int GetNumJoints()
Definition: abb_irb2400_ikfast_solver.hpp:380
ikfast::IkSolutionList
Default implementation of IkSolutionListBase.
Definition: ikfast.h:258
tesseract_kinematics::IKFastInvKin
IKFast Inverse Kinematics Implmentation.
Definition: ikfast_inv_kin.h:77
tesseract_kinematics::IKFastInvKin::clone
InverseKinematics::UPtr clone() const override
Clone the forward kinematics object.
Definition: ikfast_inv_kin.hpp:54
tesseract_kinematics::IKFastInvKin::joint_names_
std::vector< std::string > joint_names_
Joint names for the kinematic object.
Definition: ikfast_inv_kin.h:133
ikfast::IkSolutionList::GetNumSolutions
virtual size_t GetNumSolutions() const
tesseract_kinematics::IKFastInvKin::getSolverName
std::string getSolverName() const override
Get the name of the solver. Recommend using the name of the class.
Definition: ikfast_inv_kin.hpp:147
tesseract_kinematics::IKFastInvKin::getWorkingFrame
std::string getWorkingFrame() const override
Get the inverse kinematics working frame.
Definition: ikfast_inv_kin.hpp:145
tesseract_kinematics::IKFastInvKin::generateAllFreeJointStateCombinations
static std::vector< std::vector< double > > generateAllFreeJointStateCombinations(const std::vector< std::vector< double >> &free_joint_samples)
Generates all possible combinations of joint states and stores it to the free_joint_states_ class mem...
Definition: ikfast_inv_kin.hpp:150
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_kinematics::IKFastInvKin::IKFastInvKin
IKFastInvKin(const IKFastInvKin &other)
Definition: ikfast_inv_kin.hpp:56
tesseract_kinematics::IKFastInvKin::numJoints
Eigen::Index numJoints() const override
Number of joints in robot.
Definition: ikfast_inv_kin.hpp:142
tesseract_kinematics::IKFastInvKin::base_link_name_
std::string base_link_name_
Link name of first link in the kinematic object.
Definition: ikfast_inv_kin.h:131
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
ikfast.h
utils.h
Kinematics utility functions.
tesseract_kinematics::IKFastInvKin::calcInvKin
IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override
Calculates joint solutions given a pose for each tip link.
Definition: ikfast_inv_kin.hpp:69
ikfast::IkSolutionList::GetSolution
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
tesseract_kinematics::IKFastInvKin::tip_link_name_
std::string tip_link_name_
Link name of last kink in the kinematic object.
Definition: ikfast_inv_kin.h:132
ikfast_inv_kin.h
Tesseract IKFast Inverse kinematics Wrapper.
tesseract_kinematics::IKFastInvKin::getTipLinkNames
std::vector< std::string > getTipLinkNames() const override
Get the names of the tip links of the kinematics group.
Definition: ikfast_inv_kin.hpp:146
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_kinematics::IKFastInvKin::getJointNames
std::vector< std::string > getJointNames() const override
Get list of joint names for kinematic object.
Definition: ikfast_inv_kin.hpp:143
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::IKFastInvKin::getBaseLinkName
std::string getBaseLinkName() const override
Get the robot base link name.
Definition: ikfast_inv_kin.hpp:144
tesseract_kinematics::IKFastInvKin::operator=
IKFastInvKin & operator=(const IKFastInvKin &other)
Definition: ikfast_inv_kin.hpp:58
tesseract_kinematics::IKFastInvKin::solver_name_
std::string solver_name_
Name of this solver.
Definition: ikfast_inv_kin.h:134
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
macros.h
ComputeIk
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
Definition: abb_irb2400_ikfast_solver.hpp:3209
tesseract_kinematics::IKFastInvKin::free_joint_states_
std::vector< std::vector< double > > free_joint_states_
Definition: ikfast_inv_kin.h:137


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