32 #ifndef KDLCHAINIKSOLVERPOS_TL_HPP
33 #define KDLCHAINIKSOLVERPOS_TL_HPP
35 #include <kdl/chainfksolverpos_recursive.hpp>
36 #include <kdl/chainiksolvervel_pinv.hpp>
57 int CartToJnt(
const KDL::JntArray& q_init,
const KDL::Frame& p_in, KDL::JntArray& q_out,
const KDL::Twist
bounds = KDL::Twist::Zero());
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);
118 IMETHOD Twist
diffRelative(
const Frame & F_a_b1,
const Frame & F_a_b2,
double dt = 1)
120 return Twist(F_a_b1.M.Inverse() * diff(F_a_b1.p, F_a_b2.p, dt),
121 F_a_b1.M.Inverse() * diff(F_a_b1.M, F_a_b2.M, dt));