32 #include <boost/date_time.hpp>
39 chain(_chain), q_min(_q_min), q_max(_q_max), vik_solver(chain), fksolver(chain), delta_q(chain.getNrOfJoints()),
40 maxtime(_maxtime), eps(_eps), rr(_random_restart), wrap(_try_jl_wrap)
43 assert(chain.getNrOfJoints() == _q_min.data.size());
44 assert(chain.getNrOfJoints() == _q_max.data.size());
48 for (uint i = 0; i < chain.segments.size(); i++)
50 std::string type = chain.segments[i].getJoint().getTypeName();
51 if (type.find(
"Rot") != std::string::npos)
53 if (_q_max(types.size()) >= std::numeric_limits<float>::max() &&
54 _q_min(types.size()) <= std::numeric_limits<float>::lowest())
58 else if (type.find(
"Trans") != std::string::npos)
63 assert(types.size() == _q_max.data.size());
68 int ChainIkSolverPos_TL::CartToJnt(
const KDL::JntArray &q_init,
const KDL::Frame &p_in, KDL::JntArray &q_out,
const KDL::Twist _bounds)
74 boost::posix_time::ptime start_time = boost::posix_time::microsec_clock::local_time();
75 boost::posix_time::time_duration timediff;
84 fksolver.JntToCart(q_out,
f);
87 if (std::abs(delta_twist.vel.x()) <= std::abs(bounds.vel.x()))
90 if (std::abs(delta_twist.vel.y()) <= std::abs(bounds.vel.y()))
93 if (std::abs(delta_twist.vel.z()) <= std::abs(bounds.vel.z()))
96 if (std::abs(delta_twist.rot.x()) <= std::abs(bounds.rot.x()))
99 if (std::abs(delta_twist.rot.y()) <= std::abs(bounds.rot.y()))
100 delta_twist.rot.y(0);
102 if (std::abs(delta_twist.rot.z()) <= std::abs(bounds.rot.z()))
103 delta_twist.rot.z(0);
105 if (Equal(delta_twist, Twist::Zero(), eps))
108 delta_twist = diff(f, p_in);
110 vik_solver.CartToJnt(q_out, delta_twist, delta_q);
111 KDL::JntArray q_curr;
113 Add(q_out, delta_q, q_curr);
115 for (
unsigned int j = 0; j < q_min.data.size(); j++)
119 if (q_curr(j) < q_min(j))
123 q_curr(j) = q_min(j);
127 double diffangle = fmod(q_min(j) - q_curr(j), 2 *
M_PI);
130 double curr_angle = q_min(j) - diffangle + 2 *
M_PI;
131 if (curr_angle > q_max(j))
132 q_curr(j) = q_min(j);
134 q_curr(j) = curr_angle;
139 for (
unsigned int j = 0; j < q_max.data.size(); j++)
144 if (q_curr(j) > q_max(j))
148 q_curr(j) = q_max(j);
152 double diffangle = fmod(q_curr(j) - q_max(j), 2 *
M_PI);
154 double curr_angle = q_max(j) + diffangle - 2 *
M_PI;
155 if (curr_angle < q_min(j))
156 q_curr(j) = q_max(j);
158 q_curr(j) = curr_angle;
163 Subtract(q_out, q_curr, q_out);
165 if (q_out.data.isZero(boost::math::tools::epsilon<float>()))
169 for (
unsigned int j = 0; j < q_out.data.size(); j++)
171 q_curr(j) = fRand(q_curr(j) - 2 *
M_PI, q_curr(j) + 2 *
M_PI);
173 q_curr(j) = fRand(q_min(j), q_max(j));
188 timediff = boost::posix_time::microsec_clock::local_time() - start_time;
189 time_left = maxtime - timediff.total_nanoseconds() / 1000000000.0;
191 while (time_left > 0 && !aborted);
196 ChainIkSolverPos_TL::~ChainIkSolverPos_TL()