#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 48 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.
KDL::ChainIkSolverPos_TL::~ChainIkSolverPos_TL | ( | ) |
Definition at line 196 of file kdl_tl.cpp.
|
inlineprivate |
Definition at line 83 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 68 of file kdl_tl.cpp.
|
inlinestaticprivate |
Definition at line 98 of file kdl_tl.hpp.
|
inlineprivate |
Definition at line 88 of file kdl_tl.hpp.
|
inline |
Definition at line 59 of file kdl_tl.hpp.
|
friend |
Definition at line 50 of file kdl_tl.hpp.
|
private |
Definition at line 93 of file kdl_tl.hpp.
|
private |
Definition at line 69 of file kdl_tl.hpp.
|
private |
Definition at line 65 of file kdl_tl.hpp.
|
private |
Definition at line 73 of file kdl_tl.hpp.
|
private |
Definition at line 96 of file kdl_tl.hpp.
|
private |
Definition at line 76 of file kdl_tl.hpp.
|
private |
Definition at line 95 of file kdl_tl.hpp.
|
private |
Definition at line 72 of file kdl_tl.hpp.
|
private |
Definition at line 74 of file kdl_tl.hpp.
|
private |
Definition at line 67 of file kdl_tl.hpp.
|
private |
Definition at line 66 of file kdl_tl.hpp.
|
private |
Definition at line 78 of file kdl_tl.hpp.
|
private |
Definition at line 81 of file kdl_tl.hpp.
|
private |
Definition at line 71 of file kdl_tl.hpp.
|
private |
Definition at line 79 of file kdl_tl.hpp.