33 #ifndef DART_DYNAMICS_IKFAST_HPP_ 34 #define DART_DYNAMICS_IKFAST_HPP_ 38 #define IKFAST_HAS_LIBRARY 39 #include "dart/external/ikfast/ikfast.h" 41 #include "dart/dynamics/InverseKinematics.hpp" 146 const std::vector<std::size_t>& dofMap,
147 const std::vector<std::size_t>& freeDofMap,
148 const std::string& methodName =
"IKFast",
149 const Analytical::Properties& properties = Analytical::Properties());
152 const std::vector<InverseKinematics::Analytical::Solution>&
computeSolutions(
153 const Eigen::Isometry3d& desiredBodyTf)
override;
157 Eigen::Isometry3d
computeFk(
const Eigen::VectorXd& parameters);
161 const std::vector<std::size_t>&
getDofs()
const override;
165 const std::vector<std::size_t>&
getFreeDofs()
const;
212 const IkReal* targetTranspose,
213 const IkReal* targetRotation,
220 const IkReal* parameters, IkReal* targetTranspose, IkReal* targetRotation)
236 mutable std::vector<double> mFreeParams;
243 mutable std::vector<std::size_t>
mDofs;
251 std::array<IkReal, 9> mTargetRotation;
254 std::array<IkReal, 3> mTargetTranspose;
272 bool wrapCyclicSolution(
double curr,
double lb,
double ub,
double& sol);
277 #endif // DART_DYNAMICS_IKFAST_HPP_ std::vector< std::size_t > mDofs
Indices of the DegreeOfFreedoms associated to the variable parameters of this IkFast.
Definition: IkFast.hpp:243
Eigen::Isometry3d computeFk(const Eigen::VectorXd ¶meters)
Computes forward kinematics given joint positions where the dimension is the same as getNumJoints2()...
Definition: IkFast.cpp:447
std::size_t getNumJoints2() const
Returns the total number of indices of the chane.
Definition: IkFast.cpp:300
End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
Definition: IkFast.hpp:109
IkType
Inverse kinematics types supported by IkFast.
Definition: IkFast.hpp:56
virtual int getNumFreeParameters() const =0
Returns the number of free parameters users has to set apriori.
The InverseKinematics class provides a convenient way of setting up an IK optimization problem...
Definition: InverseKinematics.hpp:75
End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z...
Definition: IkFast.hpp:115
End effector reaches desired 3D rotation.
Definition: IkFast.hpp:62
virtual bool computeIk(const IkReal *targetTranspose, const IkReal *targetRotation, const IkReal *pfree, ikfast::IkSolutionListBase< IkReal > &solutions)=0
Computes the inverse kinematics solutions using the generated IKFast code.
virtual void configure() const
Configure IkFast.
Definition: IkFast.cpp:364
End effector reaches desired 6D transformation.
Definition: IkFast.hpp:59
const std::vector< std::size_t > & getFreeDofs() const
Returns the indices of the DegreeOfFreedoms that are part of the joints that IkFast solves but the va...
Definition: IkFast.cpp:282
End effector origin reaches desired 3D translation.
Definition: IkFast.hpp:65
A base class for IkFast-based analytical inverse kinematics classes.
Definition: IkFast.hpp:50
2D translation along XY plane and 1D rotation around Z axis.
Definition: IkFast.hpp:89
Analytical is a base class that should be inherited by methods that are made to solve the IK analytic...
Definition: InverseKinematics.hpp:1050
End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z...
Definition: IkFast.hpp:121
End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z...
Definition: IkFast.hpp:127
virtual int * getFreeParameters() const =0
Returns the indicies of the free parameters indexed by the chain joints.
Definition: Aspect.cpp:40
const std::vector< InverseKinematics::Analytical::Solution > & computeSolutions(const Eigen::Isometry3d &desiredBodyTf) override
Use this function to fill the entries of the mSolutions variable.
Definition: IkFast.cpp:399
virtual int getIkType() const =0
Returns the IK type.
bool mConfigured
True if this IkFast is ready to solve.
Definition: IkFast.hpp:239
Direction on end effector coordinate system reaches desired direction.
Definition: IkFast.hpp:68
IkType getIkType2() const
Returns the IK type.
Definition: IkFast.cpp:306
virtual const char * getKinematicsHash()=0
Returns a hash of all the chain values used for double checking that the correct IK is used...
virtual const char * getIkFastVersion()=0
Returns the IkFast version used to generate this file.
End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
Definition: IkFast.hpp:104
End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
Definition: IkFast.hpp:99
const std::vector< std::size_t > & getDofs() const override
Returns the indices of the DegreeOfFreedoms that are part of the joints that IkFast solves for...
Definition: IkFast.cpp:263
End effector origin and direction reaches desired 3D translation and direction.
Definition: IkFast.hpp:80
End effector origin reaches desired XY translation position, Z is ignored.
Definition: IkFast.hpp:84
std::size_t getNumFreeParameters2() const
Returns the number of free parameters users has to set apriori.
Definition: IkFast.cpp:294
virtual int getNumJoints() const =0
Returns the total number of indices of the chane.
const std::string getKinematicsHash2() const
Returns a hash of all the chain values used for double checking that the correct IK is used...
Definition: IkFast.cpp:352
IkFast(InverseKinematics *ik, 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: IkFast.cpp:248
std::string getIkFastVersion2() const
Returns the IkFast version used to generate this file.
Definition: IkFast.cpp:358
virtual bool isConfigured() const
Returns true if this IkFast is ready to solve.
Definition: IkFast.cpp:288
std::vector< std::size_t > mFreeDofs
Indices of the DegreeOfFreedoms associated to the free parameters of this IkFast. ...
Definition: IkFast.hpp:247
Direction on end effector coordinate system points to desired 3D position.
Definition: IkFast.hpp:75
Local point on end effector origin reaches desired 3D global point.
Definition: IkFast.hpp:94
virtual int getIkRealSize() const =0
Returns the size in bytes of the configured number type.
Ray on end effector coordinate system reaches desired global ray.
Definition: IkFast.hpp:71