51 int CartToJnt(
const KDL::JntArray& q_init,
const KDL::Frame& p_in, KDL::JntArray& q_out,
const KDL::Twist
bounds = KDL::Twist::Zero(),
const KDL::JntArray& q_desired = KDL::JntArray());
53 double minJoints(
const std::vector<double>& x, std::vector<double>& grad);
55 void cartSumSquaredError(
const std::vector<double>& x,
double error[]);
56 void cartDQError(
const std::vector<double>& x,
double error[]);
57 void cartL2NormError(
const std::vector<double>& x,
double error[]);
59 inline void setMaxtime(
double t)
77 std::vector<double>
lb;
78 std::vector<double>
ub;
80 const KDL::Chain
chain;
81 std::vector<double> des;
84 KDL::ChainFkSolverPos_recursive fksolver;
91 KDL::Frame targetPose;
99 std::vector<KDL::BasicJointType>
types;
103 KDL::Frame currentPose;
105 std::vector<double> best_x;
111 inline static double fRand(
double min,
double max)
113 double f = (double)rand() / RAND_MAX;
114 return min +
f * (max - min);