|
orocos_kdl
|
#include <chainiksolverpos_nr_jl.hpp>

Public Member Functions | |
| virtual int | CartToJnt (const JntArray &q_init, const Frame &p_in, JntArray &q_out) |
| ChainIkSolverPos_NR_JL (const Chain &chain, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6) | |
| ChainIkSolverPos_NR_JL (const Chain &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6) | |
| Child FK solver failed. More... | |
| int | setJointLimits (const JntArray &q_min, const JntArray &q_max) |
| const char * | strError (const int error) const |
| virtual void | updateInternalDataStructures () |
| ~ChainIkSolverPos_NR_JL () | |
Public Member Functions inherited from KDL::ChainIkSolverPos | |
| virtual | ~ChainIkSolverPos () |
Public Member Functions inherited from KDL::SolverI | |
| virtual int | getError () const |
| Return the latest error. More... | |
| SolverI () | |
| Initialize latest error to E_NOERROR. More... | |
| virtual | ~SolverI () |
Static Public Attributes | |
| static const int | E_FKSOLVERPOS_FAILED = -101 |
| Child IK solver vel failed. More... | |
| static const int | E_IKSOLVERVEL_FAILED = -100 |
Private Attributes | |
| const Chain & | chain |
| JntArray | delta_q |
| Twist | delta_twist |
| double | eps |
| Frame | f |
| ChainFkSolverPos & | fksolver |
| ChainIkSolverVel & | iksolver |
| unsigned int | maxiter |
| unsigned int | nj |
| JntArray | q_max |
| JntArray | q_min |
Additional Inherited Members | |
Public Types inherited from KDL::SolverI | |
| enum | { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2, E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6, E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8 } |
Protected Attributes inherited from KDL::SolverI | |
| int | error |
| Latest error, initialized to E_NOERROR in constructor. More... | |
Implementation of a general inverse position kinematics algorithm based on Newton-Raphson iterations to calculate the position transformation from Cartesian to joint space of a general KDL::Chain. Takes joint limits into account.
Definition at line 40 of file chainiksolverpos_nr_jl.hpp.
| KDL::ChainIkSolverPos_NR_JL::ChainIkSolverPos_NR_JL | ( | const Chain & | chain, |
| const JntArray & | q_min, | ||
| const JntArray & | q_max, | ||
| ChainFkSolverPos & | fksolver, | ||
| ChainIkSolverVel & | iksolver, | ||
| unsigned int | maxiter = 100, |
||
| double | eps = 1e-6 |
||
| ) |
Child FK solver failed.
Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain.
| chain | the chain to calculate the inverse position for |
| q_min | the minimum joint positions |
| q_max | the maximum joint positions |
| fksolver | a forward position kinematics solver |
| iksolver | an inverse velocity kinematics solver |
| maxiter | the maximum Newton-Raphson iterations, default: 100 |
| eps | the precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp) |
Definition at line 30 of file chainiksolverpos_nr_jl.cpp.
| KDL::ChainIkSolverPos_NR_JL::ChainIkSolverPos_NR_JL | ( | const Chain & | chain, |
| ChainFkSolverPos & | fksolver, | ||
| ChainIkSolverVel & | iksolver, | ||
| unsigned int | maxiter = 100, |
||
| double | eps = 1e-6 |
||
| ) |
Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain.
| chain | the chain to calculate the inverse position for |
| fksolver | a forward position kinematics solver |
| iksolver | an inverse velocity kinematics solver |
| maxiter | the maximum Newton-Raphson iterations, default: 100 |
| eps | the precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp) |
Definition at line 41 of file chainiksolverpos_nr_jl.cpp.
| KDL::ChainIkSolverPos_NR_JL::~ChainIkSolverPos_NR_JL | ( | ) |
Definition at line 111 of file chainiksolverpos_nr_jl.cpp.
|
virtual |
Calculates the joint values that correspond to the input pose given an initial guess.
| q_init | Initial guess for the joint values. |
| p_in | The input pose of the chain tip. |
| q_out | The resulting output joint values |
Implements KDL::ChainIkSolverPos.
Definition at line 62 of file chainiksolverpos_nr_jl.cpp.
Function to set the joint limits.
| q_min | minimum values for the joints |
| q_max | maximum values for the joints |
Definition at line 103 of file chainiksolverpos_nr_jl.cpp.
|
virtual |
Return a description of the latest error
Reimplemented from KDL::SolverI.
Definition at line 115 of file chainiksolverpos_nr_jl.cpp.
|
virtual |
Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.
Implements KDL::ChainIkSolverPos.
Definition at line 53 of file chainiksolverpos_nr_jl.cpp.
|
private |
Definition at line 112 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 118 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 123 of file chainiksolverpos_nr_jl.hpp.
|
static |
Child IK solver vel failed.
Definition at line 45 of file chainiksolverpos_nr_jl.hpp.
|
static |
Definition at line 44 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 120 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 122 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 117 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 116 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 119 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 113 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 115 of file chainiksolverpos_nr_jl.hpp.
|
private |
Definition at line 114 of file chainiksolverpos_nr_jl.hpp.
1.8.17