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 <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     /* @brief Manipulation metrics and penalties taken from "Workspace
00126     Geometric Characterization and Manipulability of Industrial Robots",
00127     Ming-June, Tsia, PhD Thesis, Ohio State University, 1986. 
00128     https://etd.ohiolink.edu/!etd.send_file?accession=osu1260297835
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


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