trac_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 
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 <thread>
00038 #include <mutex>
00039 #include <memory>
00040 #include <boost/date_time.hpp>
00041 
00042 namespace TRAC_IK
00043 {
00044 
00045 enum SolveType { Speed, Distance, Manip1, Manip2 };
00046 
00047 class TRAC_IK
00048 {
00049 public:
00050   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);
00051 
00052   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);
00053 
00054   ~TRAC_IK();
00055 
00056   bool getKDLChain(KDL::Chain& chain_)
00057   {
00058     chain_ = chain;
00059     return initialized;
00060   }
00061 
00062   bool getKDLLimits(KDL::JntArray& lb_, KDL::JntArray& ub_)
00063   {
00064     lb_ = lb;
00065     ub_ = ub;
00066     return initialized;
00067   }
00068 
00069   // Requires a previous call to CartToJnt()
00070   bool getSolutions(std::vector<KDL::JntArray>& solutions_)
00071   {
00072     solutions_ = solutions;
00073     return initialized && !solutions.empty();
00074   }
00075 
00076   bool getSolutions(std::vector<KDL::JntArray>& solutions_, std::vector<std::pair<double, uint> >& errors_)
00077   {
00078     errors_ = errors;
00079     return getSolutions(solutions);
00080   }
00081 
00082   bool setKDLLimits(KDL::JntArray& lb_, KDL::JntArray& ub_)
00083   {
00084     lb = lb_;
00085     ub = ub_;
00086     nl_solver.reset(new NLOPT_IK::NLOPT_IK(chain, lb, ub, maxtime, eps, NLOPT_IK::SumSq));
00087     iksolver.reset(new KDL::ChainIkSolverPos_TL(chain, lb, ub, maxtime, eps, true, true));
00088     return true;
00089   }
00090 
00091   static double JointErr(const KDL::JntArray& arr1, const KDL::JntArray& arr2)
00092   {
00093     double err = 0;
00094     for (uint i = 0; i < arr1.data.size(); i++)
00095     {
00096       err += pow(arr1(i) - arr2(i), 2);
00097     }
00098 
00099     return err;
00100   }
00101 
00102   int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist& bounds = KDL::Twist::Zero());
00103 
00104   inline void SetSolveType(SolveType _type)
00105   {
00106     solvetype = _type;
00107   }
00108 
00109 private:
00110   bool initialized;
00111   KDL::Chain chain;
00112   KDL::JntArray lb, ub;
00113   std::unique_ptr<KDL::ChainJntToJacSolver> jacsolver;
00114   double eps;
00115   double maxtime;
00116   SolveType solvetype;
00117 
00118   std::unique_ptr<NLOPT_IK::NLOPT_IK> nl_solver;
00119   std::unique_ptr<KDL::ChainIkSolverPos_TL> iksolver;
00120 
00121   boost::posix_time::ptime start_time;
00122 
00123   template<typename T1, typename T2>
00124   bool runSolver(T1& solver, T2& other_solver,
00125                  const KDL::JntArray &q_init,
00126                  const KDL::Frame &p_in);
00127 
00128   bool runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in);
00129   bool runNLOPT(const KDL::JntArray &q_init, const KDL::Frame &p_in);
00130 
00131   void normalize_seed(const KDL::JntArray& seed, KDL::JntArray& solution);
00132   void normalize_limits(const KDL::JntArray& seed, KDL::JntArray& solution);
00133 
00134   std::vector<KDL::BasicJointType> types;
00135 
00136   std::mutex mtx_;
00137   std::vector<KDL::JntArray> solutions;
00138   std::vector<std::pair<double, uint> >  errors;
00139 
00140   std::thread task1, task2;
00141   KDL::Twist bounds;
00142 
00143   bool unique_solution(const KDL::JntArray& sol);
00144 
00145   inline static double fRand(double min, double max)
00146   {
00147     double f = (double)rand() / RAND_MAX;
00148     return min + f * (max - min);
00149   }
00150 
00151   /* @brief Manipulation metrics and penalties taken from "Workspace
00152   Geometric Characterization and Manipulability of Industrial Robots",
00153   Ming-June, Tsia, PhD Thesis, Ohio State University, 1986.
00154   https://etd.ohiolink.edu/!etd.send_file?accession=osu1260297835
00155   */
00156   double manipPenalty(const KDL::JntArray&);
00157   double ManipValue1(const KDL::JntArray&);
00158   double ManipValue2(const KDL::JntArray&);
00159 
00160   inline bool myEqual(const KDL::JntArray& a, const KDL::JntArray& b)
00161   {
00162     return (a.data - b.data).isZero(1e-4);
00163   }
00164 
00165   void initialize();
00166 
00167 };
00168 
00169 inline bool TRAC_IK::runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in)
00170 {
00171   return runSolver(*iksolver.get(), *nl_solver.get(), q_init, p_in);
00172 }
00173 
00174 inline bool TRAC_IK::runNLOPT(const KDL::JntArray &q_init, const KDL::Frame &p_in)
00175 {
00176   return runSolver(*nl_solver.get(), *iksolver.get(), q_init, p_in);
00177 }
00178 
00179 }
00180 
00181 #endif


trac_ik_lib
Author(s): Patrick Beeson, Barrett Ames
autogenerated on Thu Apr 25 2019 03:39:22