- 3.0.2 models module.
Irb4600InverseKinematics.h
Go to the documentation of this file.
1 /**********************************************************************************************************************
2 This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-toolbox), copyright by ETH Zurich
3 Licensed under the BSD-2 license (see LICENSE file in main directory)
4 **********************************************************************************************************************/
5 
6 #pragma once
7 
8 #define IKFAST_HAS_LIBRARY
9 #define IKFAST_NAMESPACE irb4600_ik
10 #include <ikfast.h>
11 #include <ct/core/core.h>
12 
14 
15 using namespace ikfast;
16 
17 namespace ct {
18 namespace rbd {
19 
20 template <typename SCALAR = double>
22 {
23 public:
24  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
25 
30 
31  Irb4600InverseKinematics() = default;
32 
33  ~Irb4600InverseKinematics() = default;
34 
36  const RigidBodyPoseTpl& eeBasePose,
37  const std::vector<size_t>& freeJoints = std::vector<size_t>()) override
38  {
39  res.clear();
40  IkSolutionList<double> solutions;
41 
42  if (size_t(irb4600_ik::GetNumFreeParameters()) != freeJoints.size())
43  throw std::runtime_error("Error specifying free joints in Irb4600InverseKinematics");
44 
45  // Data needs to be in row-major form.
46  Eigen::Matrix<SCALAR, 3, 3, Eigen::RowMajor> eeBaseRotationRowMajor =
47  eeBasePose.getRotationMatrix().toImplementation();
48  const std::vector<double> freeJoints_ikf(freeJoints.begin(), freeJoints.end());
49  irb4600_ik::ComputeIk(eeBasePose.position().toImplementation().data(), eeBaseRotationRowMajor.data(),
50  freeJoints_ikf.size() > 0 ? freeJoints_ikf.data() : nullptr, solutions);
51 
52  size_t num_solutions = solutions.GetNumSolutions();
53 
54  if (num_solutions == 0)
55  return false; // no solution found
56 
57  JointState<6> sol;
58  for (size_t i = 0; i < num_solutions; ++i)
59  {
60  const IkSolutionBase<double>& solution = solutions.GetSolution(i);
61  solution.GetSolution(
62  sol.getPositions().data(), freeJoints_ikf.size() > 0 ? freeJoints_ikf.data() : nullptr);
63  res.push_back(sol.getPositions());
64  }
65 
66  if (res.size() == 0)
67  return false; // no viable solution after filtering for joint limits
68 
69  return true;
70  }
71 
73  const RigidBodyPoseTpl& eeWorldPose,
74  const RigidBodyPoseTpl& baseWorldPose,
75  const std::vector<size_t>& freeJoints = std::vector<size_t>()) override
76  {
77  return computeInverseKinematics(res, eeWorldPose.inReferenceFrame(baseWorldPose), freeJoints);
78  }
79 };
80 } /* namespace rbd */
81 } /* namespace ct */
IKFAST_API int GetNumFreeParameters()
Definition: transform6d.cpp:373
bool computeInverseKinematics(JointPositionsVector_t &res, const RigidBodyPoseTpl &eeBasePose, const std::vector< size_t > &freeJoints=std::vector< size_t >()) override
Definition: Irb4600InverseKinematics.h:35
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
Definition: transform6d.cpp:25689
for i
typename BASE::JointPositionsVector_t JointPositionsVector_t
Definition: Irb4600InverseKinematics.h:28
typename JointState< 6, SCALAR >::Position JointPosition_t
virtual void GetSolution(T *solution, const T *freevalues) const=0
typename BASE::JointPosition_t JointPosition_t
Definition: Irb4600InverseKinematics.h:27
bool computeInverseKinematics(JointPositionsVector_t &res, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const std::vector< size_t > &freeJoints=std::vector< size_t >()) override
Definition: Irb4600InverseKinematics.h:72
typename BASE::RigidBodyPoseTpl RigidBodyPoseTpl
Definition: Irb4600InverseKinematics.h:29
Definition: Irb4600InverseKinematics.h:21
JointPositionBlock getPositions()
virtual size_t GetNumSolutions() const
std::vector< JointPosition_t, Eigen::aligned_allocator< JointPosition_t > > JointPositionsVector_t