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