32 #ifndef KDLCHAINIKSOLVERPOS_TL_HPP 33 #define KDLCHAINIKSOLVERPOS_TL_HPP 35 #include <kdl/chainfksolverpos_recursive.hpp> 36 #include <kdl/chainiksolvervel_pinv.hpp> 81 std::vector<KDL::BasicJointType>
types;
98 inline static double fRand(
double min,
double max)
100 double f = (double)rand() / RAND_MAX;
101 return min + f * (max - min);
void setMaxtime(double t)
std::vector< KDL::BasicJointType > types
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
IMETHOD Twist diffRelative(const Frame &F_a_b1, const Frame &F_a_b2, double dt=1)
static double fRand(double min, double max)
KDL::ChainFkSolverPos_recursive fksolver
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist &bounds=KDL::Twist::Zero())
KDL::ChainIkSolverVel_pinv vik_solver