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 #include <trac_ik/kdl_tl.hpp>
00032 #include <boost/date_time.hpp>
00033 #include <ros/ros.h>
00034 #include <limits>
00035
00036 namespace KDL
00037 {
00038 ChainIkSolverPos_TL::ChainIkSolverPos_TL(const Chain& _chain, const JntArray& _q_min, const JntArray& _q_max, double _maxtime, double _eps, bool _random_restart, bool _try_jl_wrap):
00039 chain(_chain), q_min(_q_min), q_max(_q_max), vik_solver(_chain), fksolver(_chain), delta_q(_chain.getNrOfJoints()),
00040 maxtime(_maxtime),eps(_eps),rr(_random_restart),wrap(_try_jl_wrap)
00041 {
00042
00043 assert(chain.getNrOfJoints()==_q_min.data.size());
00044 assert(chain.getNrOfJoints()==_q_max.data.size());
00045
00046 reset();
00047
00048 for (uint i=0; i<chain.segments.size(); i++) {
00049 std::string type = chain.segments[i].getJoint().getTypeName();
00050 if (type.find("Rot")!=std::string::npos) {
00051 if (_q_max(types.size())>=std::numeric_limits<float>::max() &&
00052 _q_min(types.size())<=std::numeric_limits<float>::lowest())
00053 types.push_back(KDL::BasicJointType::Continuous);
00054 else types.push_back(KDL::BasicJointType::RotJoint);
00055 }
00056 else if (type.find("Trans")!=std::string::npos)
00057 types.push_back(KDL::BasicJointType::TransJoint);
00058
00059 }
00060
00061 assert(types.size()==_q_max.data.size());
00062 }
00063
00064
00065
00066 int ChainIkSolverPos_TL::CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist _bounds) {
00067
00068 if (aborted)
00069 return -3;
00070
00071 boost::posix_time::ptime start_time = boost::posix_time::microsec_clock::local_time();
00072 boost::posix_time::time_duration timediff;
00073 q_out = q_init;
00074 bounds = _bounds;
00075
00076
00077 double time_left;
00078
00079 do {
00080 fksolver.JntToCart(q_out,f);
00081 delta_twist = diffRelative(p_in, f);
00082
00083 if (std::abs(delta_twist.vel.x()) <= std::abs(bounds.vel.x()))
00084 delta_twist.vel.x(0);
00085
00086 if (std::abs(delta_twist.vel.y()) <= std::abs(bounds.vel.y()))
00087 delta_twist.vel.y(0);
00088
00089 if (std::abs(delta_twist.vel.z()) <= std::abs(bounds.vel.z()))
00090 delta_twist.vel.z(0);
00091
00092 if (std::abs(delta_twist.rot.x()) <= std::abs(bounds.rot.x()))
00093 delta_twist.rot.x(0);
00094
00095 if (std::abs(delta_twist.rot.y()) <= std::abs(bounds.rot.y()))
00096 delta_twist.rot.y(0);
00097
00098 if (std::abs(delta_twist.rot.z()) <= std::abs(bounds.rot.z()))
00099 delta_twist.rot.z(0);
00100
00101 if(Equal(delta_twist,Twist::Zero(),eps))
00102 return 1;
00103
00104 delta_twist = diff(f, p_in);
00105
00106 vik_solver.CartToJnt(q_out,delta_twist,delta_q);
00107 KDL::JntArray q_curr;
00108
00109 Add(q_out,delta_q,q_curr);
00110
00111 for(unsigned int j=0; j<q_min.data.size(); j++) {
00112 if (types[j]==KDL::BasicJointType::Continuous)
00113 continue;
00114 if(q_curr(j) < q_min(j))
00115 if (!wrap || types[j]==KDL::BasicJointType::TransJoint)
00116
00117 q_curr(j) = q_min(j);
00118 else {
00119
00120 double diffangle = fmod(q_min(j)-q_curr(j),2*M_PI);
00121
00122
00123 double curr_angle = q_min(j) - diffangle + 2*M_PI;
00124 if (curr_angle > q_max(j))
00125 q_curr(j) = q_min(j);
00126 else
00127 q_curr(j) = curr_angle;
00128 }
00129 }
00130
00131 for(unsigned int j=0; j<q_max.data.size(); j++) {
00132 if (types[j]==KDL::BasicJointType::Continuous)
00133 continue;
00134
00135 if(q_curr(j) > q_max(j))
00136 if (!wrap || types[j]==KDL::BasicJointType::TransJoint)
00137
00138 q_curr(j) = q_max(j);
00139 else {
00140
00141 double diffangle = fmod(q_curr(j)-q_max(j),2*M_PI);
00142
00143 double curr_angle = q_max(j) + diffangle - 2*M_PI;
00144 if (curr_angle < q_min(j))
00145 q_curr(j) = q_max(j);
00146 else
00147 q_curr(j) = curr_angle;
00148 }
00149 }
00150
00151 Subtract(q_out,q_curr,q_out);
00152
00153 if (q_out.data.isZero(boost::math::tools::epsilon<float>())) {
00154 if (rr) {
00155 for (unsigned int j=0; j<q_out.data.size(); j++)
00156 if (types[j]==KDL::BasicJointType::Continuous)
00157 q_curr(j)=fRand(q_curr(j)-2*M_PI,q_curr(j)+2*M_PI);
00158 else
00159 q_curr(j)=fRand(q_min(j),q_max(j));
00160 }
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170 }
00171
00172 q_out=q_curr;
00173
00174 timediff=boost::posix_time::microsec_clock::local_time()-start_time;
00175 time_left = maxtime - timediff.total_nanoseconds()/1000000000.0;
00176 } while (time_left > 0 && !aborted);
00177
00178 return -3;
00179 }
00180
00181 ChainIkSolverPos_TL::~ChainIkSolverPos_TL()
00182 {
00183 }
00184
00185
00186 }
00187