33 #ifndef DART_DYNAMICS_SHAREDLIBRARYIKFAST_HPP_
34 #define DART_DYNAMICS_SHAREDLIBRARYIKFAST_HPP_
65 const std::string& filePath,
66 const std::vector<std::size_t>& dofMap,
67 const std::vector<std::size_t>& freeDofMap,
68 const std::string& methodName =
"IKFast",
69 const Analytical::Properties&
properties = Analytical::Properties());
73 -> std::unique_ptr<GradientMethod>
override;
93 const IkReal* targetTranspose,
94 const IkReal* targetRotation,
95 const IkReal* freeParams,
96 ikfast::IkSolutionListBase<IkReal>& solutions)
override;
100 const IkReal* parameters,
101 IkReal* targetTranspose,
102 IkReal* targetRotation)
override;
117 const IkReal* targetTranspose,
118 const IkReal* targetRotation,
119 const IkReal* freeParams,
120 ikfast::IkSolutionListBase<IkReal>& solutions);
122 const IkReal* parameters,
123 IkReal* targetTranspose,
124 IkReal* targetRotation);
BodyPropPtr properties
Definition: SdfParser.cpp:80
A base class for IkFast-based analytical inverse kinematics classes.
Definition: IkFast.hpp:51
The InverseKinematics class provides a convenient way of setting up an IK optimization problem.
Definition: InverseKinematics.hpp:76
IkFast-based analytical inverse kinematics class.
Definition: SharedLibraryIkFast.hpp:47
int getIkRealSize() const override
Returns the size in bytes of the configured number type.
Definition: SharedLibraryIkFast.cpp:181
IkFastFuncGetIntPtr mGetFreeParameters
Definition: SharedLibraryIkFast.hpp:133
int *(*)() IkFastFuncGetIntPtr
Definition: SharedLibraryIkFast.hpp:115
IkFastFuncGetInt mGetIkType
Definition: SharedLibraryIkFast.hpp:136
SharedLibraryIkFast(InverseKinematics *ik, const std::string &filePath, const std::vector< std::size_t > &dofMap, const std::vector< std::size_t > &freeDofMap, const std::string &methodName="IKFast", const Analytical::Properties &properties=Analytical::Properties())
Constructor.
Definition: SharedLibraryIkFast.cpp:73
IkFastFuncGetInt mGetNumJoints
Definition: SharedLibraryIkFast.hpp:134
int getNumJoints() const override
Returns the total number of indices of the chane.
Definition: SharedLibraryIkFast.cpp:168
auto clone(InverseKinematics *newIK) const -> std::unique_ptr< GradientMethod > override
Enable this GradientMethod to be cloned to a new IK module.
Definition: SharedLibraryIkFast.cpp:129
IkFastFuncGetInt mGetIkRealSize
Definition: SharedLibraryIkFast.hpp:135
const char * getIkFastVersion() override
Returns the IkFast version used to generate this file.
Definition: SharedLibraryIkFast.cpp:251
IkFastFuncGetConstCharPtr mGetKinematicsHash
Definition: SharedLibraryIkFast.hpp:139
void computeFk(const IkReal *parameters, IkReal *targetTranspose, IkReal *targetRotation) override
Computes the forward kinematics solutions using the generated IKFast code.
Definition: SharedLibraryIkFast.cpp:224
int getIkType() const override
Returns the IK type.
Definition: SharedLibraryIkFast.cpp:194
bool computeIk(const IkReal *targetTranspose, const IkReal *targetRotation, const IkReal *freeParams, ikfast::IkSolutionListBase< IkReal > &solutions) override
Computes the inverse kinematics solutions using the generated IKFast code.
Definition: SharedLibraryIkFast.cpp:207
bool(*)(const IkReal *targetTranspose, const IkReal *targetRotation, const IkReal *freeParams, ikfast::IkSolutionListBase< IkReal > &solutions) IkFastFuncComputeIk
Definition: SharedLibraryIkFast.hpp:120
void(*)(const IkReal *parameters, IkReal *targetTranspose, IkReal *targetRotation) IkFastFuncComputeFk
Definition: SharedLibraryIkFast.hpp:124
std::string mFilePath
File path to the ikfast shared library.
Definition: SharedLibraryIkFast.hpp:128
IkFastFuncGetInt mGetNumFreeParameters
Definition: SharedLibraryIkFast.hpp:132
int(*)() IkFastFuncGetInt
Definition: SharedLibraryIkFast.hpp:114
IkFastFuncComputeFk mComputeFk
Definition: SharedLibraryIkFast.hpp:138
IkFastFuncGetConstCharPtr mGetIkFastVersion
Definition: SharedLibraryIkFast.hpp:140
void configure() const override
Configure IkFast.
Definition: SharedLibraryIkFast.cpp:264
const char *(*)() IkFastFuncGetConstCharPtr
Definition: SharedLibraryIkFast.hpp:125
const char * getKinematicsHash() override
Returns a hash of all the chain values used for double checking that the correct IK is used.
Definition: SharedLibraryIkFast.cpp:238
std::shared_ptr< common::SharedLibrary > mSharedLibrary
Definition: SharedLibraryIkFast.hpp:130
IkFastFuncComputeIk mComputeIk
Definition: SharedLibraryIkFast.hpp:137
int * getFreeParameters() const override
Returns the indicies of the free parameters indexed by the chain joints.
Definition: SharedLibraryIkFast.cpp:155
int getNumFreeParameters() const override
Returns the number of free parameters users has to set apriori.
Definition: SharedLibraryIkFast.cpp:142
Definition: BulletCollisionDetector.cpp:65