Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef TRAC_IK_HPP
00033 #define TRAC_IK_HPP
00034
00035 #include <trac_ik/nlopt_ik.hpp>
00036 #include <kdl/chainjnttojacsolver.hpp>
00037 #include <boost/thread.hpp>
00038 #include <boost/asio.hpp>
00039 #include <boost/scoped_ptr.hpp>
00040
00041
00042 namespace TRAC_IK {
00043
00044 enum SolveType { Speed, Distance, Manip1, Manip2 };
00045
00046 class TRAC_IK
00047 {
00048 public:
00049 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);
00050
00051 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);
00052
00053 ~TRAC_IK();
00054
00055 bool getKDLChain(KDL::Chain& chain_) {
00056 chain_=chain;
00057 return initialized;
00058 }
00059
00060 bool getKDLLimits(KDL::JntArray& lb_, KDL::JntArray& ub_) {
00061 lb_=lb;
00062 ub_=ub;
00063 return initialized;
00064 }
00065
00066
00067 static double JointErr(const KDL::JntArray& arr1, const KDL::JntArray& arr2) {
00068 double err = 0;
00069 for (uint i=0; i<arr1.data.size(); i++) {
00070 err += pow(arr1(i) - arr2(i),2);
00071 }
00072
00073 return err;
00074 }
00075
00076 int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist& bounds=KDL::Twist::Zero());
00077
00078 inline void SetSolveType(SolveType _type) {
00079 solvetype = _type;
00080 }
00081
00082 private:
00083 bool initialized;
00084 KDL::Chain chain;
00085 KDL::JntArray lb, ub;
00086 boost::scoped_ptr<KDL::ChainJntToJacSolver> jacsolver;
00087 double eps;
00088 double maxtime;
00089 SolveType solvetype;
00090
00091 boost::scoped_ptr<NLOPT_IK::NLOPT_IK> nl_solver;
00092 boost::scoped_ptr<KDL::ChainIkSolverPos_TL> iksolver;
00093
00094 boost::posix_time::ptime start_time;
00095
00096 bool runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in);
00097
00098
00099 bool runNLOPT(const KDL::JntArray &q_init, const KDL::Frame &p_in);
00100
00101 void normalize_seed(const KDL::JntArray& seed, KDL::JntArray& solution);
00102 void normalize_limits(const KDL::JntArray& seed, KDL::JntArray& solution);
00103
00104
00105 std::vector<KDL::BasicJointType> types;
00106
00107 boost::mutex mtx_;
00108 std::vector<KDL::JntArray> solutions;
00109 std::vector<std::pair<double,uint> > errors;
00110
00111
00112 boost::asio::io_service io_service;
00113 boost::thread_group threads;
00114 boost::asio::io_service::work work;
00115 KDL::Twist bounds;
00116
00117 bool unique_solution(const KDL::JntArray& sol);
00118
00119 inline static double fRand(double min, double max)
00120 {
00121 double f = (double)rand() / RAND_MAX;
00122 return min + f * (max - min);
00123 }
00124
00125
00126
00127
00128
00129
00130 double manipPenalty(const KDL::JntArray&);
00131 double ManipValue1(const KDL::JntArray&);
00132 double ManipValue2(const KDL::JntArray&);
00133
00134 inline bool myEqual(const KDL::JntArray& a, const KDL::JntArray& b) {
00135 return (a.data-b.data).isZero(1e-4);
00136 }
00137
00138 void initialize();
00139
00140 };
00141
00142 }
00143
00144 #endif