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)
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());
74 boost::posix_time::ptime start_time = boost::posix_time::microsec_clock::local_time();
75 boost::posix_time::time_duration timediff;
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;
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);
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);
IMETHOD doubleVel diff(const doubleVel &a, const doubleVel &b, double dt=1.0)
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)
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)
void Subtract(const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &dest)
std::vector< KDL::BasicJointType > types
IMETHOD Twist diffRelative(const Frame &F_a_b1, const Frame &F_a_b2, double dt=1)
static double fRand(double min, double max)
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
void Add(const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &dest)
KDL::ChainFkSolverPos_recursive fksolver
IMETHOD bool Equal(const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
unsigned int getNrOfJoints() const
KDL::ChainIkSolverVel_pinv vik_solver
std::vector< Segment > segments
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist bounds=KDL::Twist::Zero())