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