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[]);
77 std::vector<double>
lb;
78 std::vector<double>
ub;
81 std::vector<double>
des;
99 std::vector<KDL::BasicJointType>
types;
111 inline static double fRand(
double min,
double max)
113 double f = (double)rand() / RAND_MAX;
114 return min + f * (max - min);
std::vector< KDL::BasicJointType > types
void setMaxtime(double t)
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist &bounds=KDL::Twist::Zero())
std::vector< double > des
static double fRand(double min, double max)
KDL::ChainFkSolverPos_recursive fksolver
std::vector< double > best_x