33#ifndef DART_DYNAMICS_IKFAST_HPP_
34#define DART_DYNAMICS_IKFAST_HPP_
38#define IKFAST_HAS_LIBRARY
39#include "dart/external/ikfast/ikfast.h"
67 const std::vector<std::size_t>& dofMap,
68 const std::vector<std::size_t>& freeDofMap,
69 const std::string& methodName =
"IKFast",
70 const Analytical::Properties&
properties = Analytical::Properties());
74 ->
const std::vector<InverseKinematics::Analytical::Solution>&
override;
77 auto getDofs()
const ->
const std::vector<std::size_t>&
override;
94 ikfast::IkSolutionListBase<IkReal>& solutions) = 0;
112 mutable std::vector<std::size_t>
mDofs;
BodyPropPtr properties
Definition SdfParser.cpp:80
A base class for IkFast-based analytical inverse kinematics classes.
Definition IkFast.hpp:51
virtual bool isConfigured() const
Returns true if this IkFast is ready to solve.
Definition IkFast.cpp:236
auto computeSolutions(const Eigen::Isometry3d &desiredBodyTf) -> const std::vector< InverseKinematics::Analytical::Solution > &override
Use this function to fill the entries of the mSolutions variable.
Definition IkFast.cpp:277
std::array< IkReal, 9 > mTargetRotation
Cache data for the target rotation used by IKFast.
Definition IkFast.hpp:120
virtual bool computeIk(const IkReal *mTargetTranspose, const IkReal *mTargetRotation, const IkReal *pfree, ikfast::IkSolutionListBase< IkReal > &solutions)=0
Computes the inverse kinematics solutions using the generated IKFast code.
virtual int getIkType() const =0
virtual int getIkRealSize() const =0
auto getDofs() const -> const std::vector< std::size_t > &override
Get a list of the DOFs that will be included in the entries of the solutions returned by getSolutions...
Definition IkFast.cpp:217
bool mConfigured
True if this IkFast is ready to solve.
Definition IkFast.hpp:108
virtual const char * getIkFastVersion()=0
virtual int * getFreeParameters() const =0
std::vector< double > mFreeParams
Definition IkFast.hpp:105
std::vector< std::size_t > mDofs
Indices of the DegreeOfFreedoms associated to the variable parameters of this IkFast.
Definition IkFast.hpp:112
std::vector< std::size_t > mFreeDofs
Indices of the DegreeOfFreedoms associated to the free parameters of this IkFast.
Definition IkFast.hpp:116
virtual int getNumFreeParameters() const =0
virtual void configure() const
Configure IkFast.
Definition IkFast.cpp:242
virtual int getNumJoints() const =0
virtual const char * getKinematicsHash()=0
std::array< IkReal, 3 > mTargetTranspose
Cache data for the target translation used by IKFast.
Definition IkFast.hpp:123
Analytical is a base class that should be inherited by methods that are made to solve the IK analytic...
Definition InverseKinematics.hpp:965
The InverseKinematics class provides a convenient way of setting up an IK optimization problem.
Definition InverseKinematics.hpp:76
Definition BulletCollisionDetector.cpp:63