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 {
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