36 #include <kdl/chainjnttojacsolver.hpp> 40 #include <boost/date_time.hpp> 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);
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);
94 for (uint i = 0; i < arr1.
data.size(); i++)
96 err +=
pow(arr1(i) - arr2(i), 2);
119 std::unique_ptr<KDL::ChainIkSolverPos_TL>
iksolver;
123 template<
typename T1,
typename T2>
124 bool runSolver(T1& solver, T2& other_solver,
134 std::vector<KDL::BasicJointType>
types;
138 std::vector<std::pair<double, uint> >
errors;
145 inline static double fRand(
double min,
double max)
147 double f = (double)rand() / RAND_MAX;
148 return min + f * (max - min);
162 return (a.
data - b.
data).isZero(1e-4);
171 return runSolver(*iksolver.get(), *nl_solver.get(), q_init, p_in);
176 return runSolver(*nl_solver.get(), *iksolver.get(), q_init, p_in);
bool myEqual(const KDL::JntArray &a, const KDL::JntArray &b)
bool getKDLLimits(KDL::JntArray &lb_, KDL::JntArray &ub_)
ROSCONSOLE_DECL void initialize()
std::vector< KDL::JntArray > solutions
std::unique_ptr< KDL::ChainIkSolverPos_TL > iksolver
bool setKDLLimits(KDL::JntArray &lb_, KDL::JntArray &ub_)
std::unique_ptr< NLOPT_IK::NLOPT_IK > nl_solver
std::vector< std::pair< double, uint > > errors
std::vector< KDL::BasicJointType > types
std::unique_ptr< KDL::ChainJntToJacSolver > jacsolver
static double JointErr(const KDL::JntArray &arr1, const KDL::JntArray &arr2)
static double fRand(double min, double max)
void SetSolveType(SolveType _type)
boost::posix_time::ptime start_time
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
bool getSolutions(std::vector< KDL::JntArray > &solutions_, std::vector< std::pair< double, uint > > &errors_)
bool getKDLChain(KDL::Chain &chain_)
bool getSolutions(std::vector< KDL::JntArray > &solutions_)