DART 6.12.2
Loading...
Searching...
No Matches
IkFast.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2021, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33#ifndef DART_DYNAMICS_IKFAST_HPP_
34#define DART_DYNAMICS_IKFAST_HPP_
35
36#include <array>
37
38#define IKFAST_HAS_LIBRARY
40#include "dart/external/ikfast/ikfast.h"
41
42namespace dart {
43namespace dynamics {
44
50{
51public:
53 // Following conversion is referred from:
54 // https://github.com/rdiankov/openrave/blob/b1ebe135b4217823ebdf56d9af5fe89b29723603/include/openrave/openrave.h#L575-L623
130
143 IkFast(
145 const std::vector<std::size_t>& dofMap,
146 const std::vector<std::size_t>& freeDofMap,
147 const std::string& methodName = "IKFast",
148 const Analytical::Properties& properties = Analytical::Properties());
149
150 // Documentation inherited.
151 const std::vector<InverseKinematics::Analytical::Solution>& computeSolutions(
152 const Eigen::Isometry3d& desiredBodyTf) override;
153
156 Eigen::Isometry3d computeFk(const Eigen::VectorXd& parameters);
157
160 const std::vector<std::size_t>& getDofs() const override;
161
164 const std::vector<std::size_t>& getFreeDofs() const;
165
167 virtual bool isConfigured() const;
168
170 std::size_t getNumFreeParameters2() const;
171 // TODO(JS): Rename to getNumFreeParameters() in DART 7
172
174 std::size_t getNumJoints2() const;
175 // TODO(JS): Rename to getNumJoints in DART 7
176
178 IkType getIkType2() const;
179 // TODO(JS): Rename to getIkType() in DART 7
180
183 const std::string getKinematicsHash2() const;
184 // TODO(JS): Rename to getKinematicsHash() in DART 7
185
187 std::string getIkFastVersion2() const;
188 // TODO(JS): Rename to getIkFastVersion() in DART 7
189
190protected:
192 virtual int getNumFreeParameters() const = 0;
193 // TODO(JS): Remove in DART 7
194
196 virtual int* getFreeParameters() const = 0;
197 // TODO(JS): Remove in DART 7
198
200 virtual int getNumJoints() const = 0;
201 // TODO(JS): Remove in DART 7
202
204 virtual int getIkRealSize() const = 0;
205
207 virtual int getIkType() const = 0;
208
210 virtual bool computeIk(
211 const IkReal* targetTranspose,
212 const IkReal* targetRotation,
213 const IkReal* pfree,
214 ikfast::IkSolutionListBase<IkReal>& solutions)
215 = 0;
216
218 virtual void computeFk(
219 const IkReal* parameters, IkReal* targetTranspose, IkReal* targetRotation)
220 = 0;
221
224 virtual const char* getKinematicsHash() = 0;
225 // TODO(JS): Rename in DART 7
226
228 virtual const char* getIkFastVersion() = 0;
229 // TODO(JS): Rename in DART 7
230
233 virtual void configure() const;
234
235 mutable std::vector<double> mFreeParams;
236
238 mutable bool mConfigured;
239
242 mutable std::vector<std::size_t> mDofs;
243
246 mutable std::vector<std::size_t> mFreeDofs;
247
248private:
250 std::array<IkReal, 9> mTargetRotation;
251
253 std::array<IkReal, 3> mTargetTranspose;
254};
255
271bool wrapCyclicSolution(double curr, double lb, double ub, double& sol);
272
273} // namespace dynamics
274} // namespace dart
275
276#endif // DART_DYNAMICS_IKFAST_HPP_
BodyPropPtr properties
Definition SdfParser.cpp:80
A base class for IkFast-based analytical inverse kinematics classes.
Definition IkFast.hpp:50
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 bool isConfigured() const
Returns true if this IkFast is ready to solve.
Definition IkFast.cpp:288
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
std::array< IkReal, 9 > mTargetRotation
Cache data for the target rotation used by IKFast.
Definition IkFast.hpp:250
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 int getIkType() const =0
Returns the IK type.
virtual int getIkRealSize() const =0
Returns the size in bytes of the configured number type.
bool mConfigured
True if this IkFast is ready to solve.
Definition IkFast.hpp:238
virtual const char * getIkFastVersion()=0
Returns the IkFast version used to generate this file.
virtual int * getFreeParameters() const =0
Returns the indicies of the free parameters indexed by the chain joints.
std::string getIkFastVersion2() const
Returns the IkFast version used to generate this file.
Definition IkFast.cpp:358
std::size_t getNumFreeParameters2() const
Returns the number of free parameters users has to set apriori.
Definition IkFast.cpp:294
std::size_t getNumJoints2() const
Returns the total number of indices of the chane.
Definition IkFast.cpp:300
std::vector< double > mFreeParams
Definition IkFast.hpp:235
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
std::vector< std::size_t > mDofs
Indices of the DegreeOfFreedoms associated to the variable parameters of this IkFast.
Definition IkFast.hpp:242
std::vector< std::size_t > mFreeDofs
Indices of the DegreeOfFreedoms associated to the free parameters of this IkFast.
Definition IkFast.hpp:246
virtual int getNumFreeParameters() const =0
Returns the number of free parameters users has to set apriori.
virtual void configure() const
Configure IkFast.
Definition IkFast.cpp:364
IkType
Inverse kinematics types supported by IkFast.
Definition IkFast.hpp:56
@ TRANSLATION_3D
End effector origin reaches desired 3D translation.
Definition IkFast.hpp:64
@ DIRECTION_3D
Direction on end effector coordinate system reaches desired direction.
Definition IkFast.hpp:67
@ TRANSLATION_Y_AXIS_ANGLE_X_NORM_4D
End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z...
Definition IkFast.hpp:120
@ UNKNOWN
Definition IkFast.hpp:128
@ TRANSLATION_Y_AXIS_ANGLE_4D
End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
Definition IkFast.hpp:103
@ LOOKAT_3D
Direction on end effector coordinate system points to desired 3D position.
Definition IkFast.hpp:74
@ ROTATION_3D
End effector reaches desired 3D rotation.
Definition IkFast.hpp:61
@ TRANSLATION_Z_AXIS_ANGLE_4D
End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
Definition IkFast.hpp:108
@ TRANSLATION_Z_AXIS_ANGLE_Y_NORM_4D
End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z...
Definition IkFast.hpp:126
@ TRANSLATION_DIRECTION_5D
End effector origin and direction reaches desired 3D translation and direction.
Definition IkFast.hpp:79
@ TRANSLATION_XY_ORIENTATION_3D
2D translation along XY plane and 1D rotation around Z axis.
Definition IkFast.hpp:88
@ TRANSFORM_6D
End effector reaches desired 6D transformation.
Definition IkFast.hpp:58
@ RAY_4D
Ray on end effector coordinate system reaches desired global ray.
Definition IkFast.hpp:70
@ TRANSLATION_XY_2D
End effector origin reaches desired XY translation position, Z is ignored.
Definition IkFast.hpp:83
@ TRANSLATION_LOCAL_GLOBAL_6D
Local point on end effector origin reaches desired 3D global point.
Definition IkFast.hpp:93
@ TRANSLATION_X_AXIS_ANGLE_4D
End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with...
Definition IkFast.hpp:98
@ TRANSLATION_X_AXIS_ANGLE_Z_NORM_4D
End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z...
Definition IkFast.hpp:114
virtual int getNumJoints() const =0
Returns the total number of indices of the chane.
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 void computeFk(const IkReal *parameters, IkReal *targetTranspose, IkReal *targetRotation)=0
Computes the forward kinematics solutions using the generated IKFast code.
std::array< IkReal, 3 > mTargetTranspose
Cache data for the target translation used by IKFast.
Definition IkFast.hpp:253
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
Eigen::Isometry3d computeFk(const Eigen::VectorXd &parameters)
Computes forward kinematics given joint positions where the dimension is the same as getNumJoints2().
Definition IkFast.cpp:447
Analytical is a base class that should be inherited by methods that are made to solve the IK analytic...
Definition InverseKinematics.hpp:1051
The InverseKinematics class provides a convenient way of setting up an IK optimization problem.
Definition InverseKinematics.hpp:76
bool wrapCyclicSolution(double currentValue, double lb, double ub, double &solutionValue)
Tries to wrap a single dof IK solution, from IKFast, in the range of joint limits.
Definition IkFast.cpp:469
Definition BulletCollisionDetector.cpp:60