#include <kdl_tl.hpp>
Public Member Functions | |
int | CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist bounds=KDL::Twist::Zero()) |
ChainIkSolverPos_TL (const Chain &chain, const JntArray &q_min, const JntArray &q_max, double maxtime=0.005, double eps=1e-3, bool random_restart=false, bool try_jl_wrap=false) | |
void | setMaxtime (double t) |
~ChainIkSolverPos_TL () | |
Private Member Functions | |
void | abort () |
void | reset () |
Static Private Member Functions | |
static double | fRand (double min, double max) |
Private Attributes | |
bool | aborted |
KDL::Twist | bounds |
const Chain | chain |
JntArray | delta_q |
Twist | delta_twist |
double | eps |
Frame | f |
KDL::ChainFkSolverPos_recursive | fksolver |
double | maxtime |
JntArray | q_max |
JntArray | q_min |
bool | rr |
std::vector< KDL::BasicJointType > | types |
KDL::ChainIkSolverVel_pinv | vik_solver |
bool | wrap |
Friends | |
class | TRAC_IK::TRAC_IK |
Definition at line 46 of file kdl_tl.hpp.
KDL::ChainIkSolverPos_TL::ChainIkSolverPos_TL | ( | const Chain & | chain, |
const JntArray & | q_min, | ||
const JntArray & | q_max, | ||
double | maxtime = 0.005 , |
||
double | eps = 1e-3 , |
||
bool | random_restart = false , |
||
bool | try_jl_wrap = false |
||
) |
Definition at line 38 of file kdl_tl.cpp.
Definition at line 181 of file kdl_tl.cpp.
void KDL::ChainIkSolverPos_TL::abort | ( | ) | [inline, private] |
Definition at line 78 of file kdl_tl.hpp.
int KDL::ChainIkSolverPos_TL::CartToJnt | ( | const KDL::JntArray & | q_init, |
const KDL::Frame & | p_in, | ||
KDL::JntArray & | q_out, | ||
const KDL::Twist | bounds = KDL::Twist::Zero() |
||
) |
Definition at line 66 of file kdl_tl.cpp.
static double KDL::ChainIkSolverPos_TL::fRand | ( | double | min, |
double | max | ||
) | [inline, static, private] |
Definition at line 91 of file kdl_tl.hpp.
void KDL::ChainIkSolverPos_TL::reset | ( | ) | [inline, private] |
Definition at line 82 of file kdl_tl.hpp.
void KDL::ChainIkSolverPos_TL::setMaxtime | ( | double | t | ) | [inline] |
Definition at line 57 of file kdl_tl.hpp.
friend class TRAC_IK::TRAC_IK [friend] |
Definition at line 48 of file kdl_tl.hpp.
bool KDL::ChainIkSolverPos_TL::aborted [private] |
Definition at line 86 of file kdl_tl.hpp.
KDL::Twist KDL::ChainIkSolverPos_TL::bounds [private] |
Definition at line 64 of file kdl_tl.hpp.
const Chain KDL::ChainIkSolverPos_TL::chain [private] |
Definition at line 60 of file kdl_tl.hpp.
JntArray KDL::ChainIkSolverPos_TL::delta_q [private] |
Definition at line 68 of file kdl_tl.hpp.
Twist KDL::ChainIkSolverPos_TL::delta_twist [private] |
Definition at line 89 of file kdl_tl.hpp.
double KDL::ChainIkSolverPos_TL::eps [private] |
Definition at line 71 of file kdl_tl.hpp.
Frame KDL::ChainIkSolverPos_TL::f [private] |
Definition at line 88 of file kdl_tl.hpp.
Definition at line 67 of file kdl_tl.hpp.
double KDL::ChainIkSolverPos_TL::maxtime [private] |
Definition at line 69 of file kdl_tl.hpp.
JntArray KDL::ChainIkSolverPos_TL::q_max [private] |
Definition at line 62 of file kdl_tl.hpp.
JntArray KDL::ChainIkSolverPos_TL::q_min [private] |
Definition at line 61 of file kdl_tl.hpp.
bool KDL::ChainIkSolverPos_TL::rr [private] |
Definition at line 73 of file kdl_tl.hpp.
std::vector<KDL::BasicJointType> KDL::ChainIkSolverPos_TL::types [private] |
Definition at line 76 of file kdl_tl.hpp.
Definition at line 66 of file kdl_tl.hpp.
bool KDL::ChainIkSolverPos_TL::wrap [private] |
Definition at line 74 of file kdl_tl.hpp.