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 #ifndef NLOPT_IK_HPP
00032 #define NLOPT_IK_HPP
00033
00034 #include <trac_ik/kdl_tl.hpp>
00035 #include <nlopt.hpp>
00036
00037
00038 namespace NLOPT_IK {
00039
00040 enum OptType { Joint, DualQuat, SumSq, L2 };
00041
00042
00043 class NLOPT_IK
00044 {
00045 friend class TRAC_IK::TRAC_IK;
00046 public:
00047 NLOPT_IK(const KDL::Chain& chain,const KDL::JntArray& q_min, const KDL::JntArray& q_max, double maxtime=0.005, double eps=1e-3, OptType type=SumSq);
00048
00049 ~NLOPT_IK() {};
00050 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());
00051
00052 double minJoints(const std::vector<double>& x, std::vector<double>& grad);
00053
00054 void cartSumSquaredError(const std::vector<double>& x, double error[]);
00055 void cartDQError(const std::vector<double>& x, double error[]);
00056 void cartL2NormError(const std::vector<double>& x, double error[]);
00057
00058 inline void setMaxtime(double t) { maxtime = t; }
00059
00060 private:
00061
00062 inline void abort() {
00063 aborted = true;
00064 }
00065
00066 inline void reset() {
00067 aborted = false;
00068 }
00069
00070
00071 std::vector<double> lb;
00072 std::vector<double> ub;
00073
00074 const KDL::Chain chain;
00075 std::vector<double> des;
00076
00077
00078 KDL::ChainFkSolverPos_recursive fksolver;
00079
00080 double maxtime;
00081 double eps;
00082 int iter_counter;
00083 OptType TYPE;
00084
00085 KDL::Frame targetPose;
00086 KDL::Frame z_up ;
00087 KDL::Frame x_out;
00088 KDL::Frame y_out;
00089 KDL::Frame z_target;
00090 KDL::Frame x_target;
00091 KDL::Frame y_target;
00092
00093 std::vector<KDL::BasicJointType> types;
00094
00095 nlopt::opt opt;
00096
00097 KDL::Frame currentPose;
00098
00099 std::vector<double> best_x;
00100 int progress;
00101 bool aborted;
00102
00103 KDL::Twist bounds;
00104
00105 inline static double fRand(double min, double max)
00106 {
00107 double f = (double)rand() / RAND_MAX;
00108 return min + f * (max - min);
00109 }
00110
00111
00112 };
00113
00114 }
00115
00116 #endif