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
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 class TRAC_IK;
00040 }
00041
00042 namespace KDL {
00043
00044 enum BasicJointType { RotJoint, TransJoint, Continuous };
00045
00046 class ChainIkSolverPos_TL
00047 {
00048 friend class TRAC_IK::TRAC_IK;
00049
00050 public:
00051 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);
00052
00053 ~ChainIkSolverPos_TL();
00054
00055 int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out, const KDL::Twist bounds=KDL::Twist::Zero());
00056
00057 inline void setMaxtime(double t) { maxtime = t; }
00058
00059 private:
00060 const Chain chain;
00061 JntArray q_min;
00062 JntArray q_max;
00063
00064 KDL::Twist bounds;
00065
00066 KDL::ChainIkSolverVel_pinv vik_solver;
00067 KDL::ChainFkSolverPos_recursive fksolver;
00068 JntArray delta_q;
00069 double maxtime;
00070
00071 double eps;
00072
00073 bool rr;
00074 bool wrap;
00075
00076 std::vector<KDL::BasicJointType> types;
00077
00078 inline void abort() {
00079 aborted = true;
00080 }
00081
00082 inline void reset() {
00083 aborted = false;
00084 }
00085
00086 bool aborted;
00087
00088 Frame f;
00089 Twist delta_twist;
00090
00091 inline static double fRand(double min, double max)
00092 {
00093 double f = (double)rand() / RAND_MAX;
00094 return min + f * (max - min);
00095 }
00096
00097
00098 };
00099
00111 IMETHOD Twist diffRelative(const Frame & F_a_b1, const Frame & F_a_b2, double dt = 1)
00112 {
00113 return Twist(F_a_b1.M.Inverse() * diff(F_a_b1.p, F_a_b2.p, dt),
00114 F_a_b1.M.Inverse() * diff(F_a_b1.M, F_a_b2.M, dt));
00115 }
00116
00117 }
00118
00119 #endif