36 #include <kdl/chainjnttojacsolver.hpp>
40 #include <boost/date_time.hpp>
50 TRAC_IK(
const KDL::Chain& _chain,
const KDL::JntArray& _q_min,
const KDL::JntArray& _q_max,
double _maxtime = 0.005,
double _eps = 1e-5,
SolveType _type =
Speed);
52 TRAC_IK(
const std::string& base_link,
const std::string& tip_link,
const std::string& URDF_param =
"/robot_description",
double _maxtime = 0.005,
double _eps = 1e-5,
SolveType _type =
Speed);
56 bool getKDLChain(KDL::Chain& chain_)
62 bool getKDLLimits(KDL::JntArray& lb_, KDL::JntArray& ub_)
70 bool getSolutions(std::vector<KDL::JntArray>& solutions_)
72 solutions_ = solutions;
73 return initialized && !solutions.empty();
76 bool getSolutions(std::vector<KDL::JntArray>& solutions_, std::vector<std::pair<double, uint> >& errors_)
79 return getSolutions(solutions_);
82 bool setKDLLimits(KDL::JntArray& lb_, KDL::JntArray& ub_)
91 static double JointErr(
const KDL::JntArray& arr1,
const KDL::JntArray& arr2)
94 for (uint i = 0; i < arr1.data.size(); i++)
96 err += pow(arr1(i) - arr2(i), 2);
102 int CartToJnt(
const KDL::JntArray &q_init,
const KDL::Frame &p_in, KDL::JntArray &q_out,
const KDL::Twist& bounds = KDL::Twist::Zero());
112 KDL::JntArray lb, ub;
113 std::unique_ptr<KDL::ChainJntToJacSolver> jacsolver;
118 std::unique_ptr<NLOPT_IK::NLOPT_IK> nl_solver;
119 std::unique_ptr<KDL::ChainIkSolverPos_TL> iksolver;
121 boost::posix_time::ptime start_time;
123 template<
typename T1,
typename T2>
124 bool runSolver(T1& solver, T2& other_solver,
125 const KDL::JntArray &q_init,
126 const KDL::Frame &p_in);
128 bool runKDL(
const KDL::JntArray &q_init,
const KDL::Frame &p_in);
129 bool runNLOPT(
const KDL::JntArray &q_init,
const KDL::Frame &p_in);
131 void normalize_seed(
const KDL::JntArray& seed, KDL::JntArray& solution);
132 void normalize_limits(
const KDL::JntArray& seed, KDL::JntArray& solution);
134 std::vector<KDL::BasicJointType> types;
137 std::vector<KDL::JntArray> solutions;
138 std::vector<std::pair<double, uint> > errors;
140 std::thread task1, task2;
143 bool unique_solution(
const KDL::JntArray& sol);
145 inline static double fRand(
double min,
double max)
147 double f = (double)rand() / RAND_MAX;
148 return min +
f * (max - min);
156 double manipPenalty(
const KDL::JntArray&);
157 double ManipValue1(
const KDL::JntArray&);
158 double ManipValue2(
const KDL::JntArray&);
160 inline bool myEqual(
const KDL::JntArray& a,
const KDL::JntArray& b)
162 return (a.data - b.data).isZero(1e-4);
169 inline bool TRAC_IK::runKDL(
const KDL::JntArray &q_init,
const KDL::Frame &p_in)
171 return runSolver(*iksolver.get(), *nl_solver.get(), q_init, p_in);
174 inline bool TRAC_IK::runNLOPT(
const KDL::JntArray &q_init,
const KDL::Frame &p_in)
176 return runSolver(*nl_solver.get(), *iksolver.get(), q_init, p_in);