kdl_tl.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 KDLCHAINIKSOLVERPOS_TL_HPP
00033 #define KDLCHAINIKSOLVERPOS_TL_HPP
00034 
00035 #include <kdl/chainfksolverpos_recursive.hpp>
00036 #include <kdl/chainiksolvervel_pinv.hpp>
00037 
00038 namespace TRAC_IK
00039 {
00040 class TRAC_IK;
00041 }
00042 
00043 namespace KDL
00044 {
00045 
00046 enum BasicJointType { RotJoint, TransJoint, Continuous };
00047 
00048 class ChainIkSolverPos_TL
00049 {
00050   friend class TRAC_IK::TRAC_IK;
00051 
00052 public:
00053   ChainIkSolverPos_TL(const Chain& chain, const JntArray& q_min, const JntArray& q_max, double maxtime = 0.005, double eps = 1e-3, bool random_restart = false, bool try_jl_wrap = false);
00054 
00055   ~ChainIkSolverPos_TL();
00056 
00057   int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out, const KDL::Twist bounds = KDL::Twist::Zero());
00058 
00059   inline void setMaxtime(double t)
00060   {
00061     maxtime = t;
00062   }
00063 
00064 private:
00065   const Chain chain;
00066   JntArray q_min;
00067   JntArray q_max;
00068 
00069   KDL::Twist bounds;
00070 
00071   KDL::ChainIkSolverVel_pinv vik_solver;
00072   KDL::ChainFkSolverPos_recursive fksolver;
00073   JntArray delta_q;
00074   double maxtime;
00075 
00076   double eps;
00077 
00078   bool rr;
00079   bool wrap;
00080 
00081   std::vector<KDL::BasicJointType> types;
00082 
00083   inline void abort()
00084   {
00085     aborted = true;
00086   }
00087 
00088   inline void reset()
00089   {
00090     aborted = false;
00091   }
00092 
00093   bool aborted;
00094 
00095   Frame f;
00096   Twist delta_twist;
00097 
00098   inline static double fRand(double min, double max)
00099   {
00100     double f = (double)rand() / RAND_MAX;
00101     return min + f * (max - min);
00102   }
00103 
00104 
00105 };
00106 
00118 IMETHOD Twist diffRelative(const Frame & F_a_b1, const Frame & F_a_b2, double dt = 1)
00119 {
00120   return Twist(F_a_b1.M.Inverse() * diff(F_a_b1.p, F_a_b2.p, dt),
00121                F_a_b1.M.Inverse() * diff(F_a_b1.M, F_a_b2.M, dt));
00122 }
00123 
00124 }
00125 
00126 #endif


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