nlopt_ik.hpp
Go to the documentation of this file.
00001 /********************************************************************************
00002 Copyright (c) 2015, TRACLabs, Inc.
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without modification,
00006  are permitted provided that the following conditions are met:
00007 
00008     1. Redistributions of source code must retain the above copyright notice, 
00009        this list of conditions and the following disclaimer.
00010 
00011     2. Redistributions in binary form must reproduce the above copyright notice,
00012        this list of conditions and the following disclaimer in the documentation 
00013        and/or other materials provided with the distribution.
00014 
00015     3. Neither the name of the copyright holder nor the names of its contributors
00016        may be used to endorse or promote products derived from this software 
00017        without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
00022 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
00023 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 
00024 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 
00025 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00026 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE 
00027 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
00028 OF THE POSSIBILITY OF SUCH DAMAGE.
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     //  void cartFourPointError(const std::vector<double>& x, double error[]);
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


trac_ik_lib
Author(s): Patrick Beeson, Barrett Ames
autogenerated on Thu Sep 21 2017 02:53:02