34 unsigned int _maxiter,
double _eps) :
35 chain(_chain), q_min(chain.getNrOfJoints()), q_max(chain.getNrOfJoints()), fksolver(_fksolver),
36 iksolver(_iksolver), delta_q(_chain.getNrOfJoints()),
37 maxiter(_maxiter), eps(_eps)
46 Twist delta_twist_temp;
56 if (iksolver_wdls != NULL)
64 delta_twist_temp.
vel.
x(0.0);
68 delta_twist_temp.
vel.
y(0.0);
72 delta_twist_temp.
vel.
z(0.0);
76 delta_twist_temp.
rot.
x(0.0);
80 delta_twist_temp.
rot.
y(0.0);
84 delta_twist_temp.
rot.
z(0.0);
96 for (
unsigned int j = 0; j <
q_min.
rows(); j++)
98 if (q_out(j) <
q_min(j))
105 for (
unsigned int j = 0; j <
q_max.
rows(); j++)
107 if (q_out(j) >
q_max(j))
IMETHOD doubleVel diff(const doubleVel &a, const doubleVel &b, double dt=1.0)
Eigen::MatrixXd getWeightTS()
unsigned int rows() const
void Add(const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &dest)
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)=0
IMETHOD bool Equal(const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
ChainIkSolverPos_NR_JL_coupling(const Chain_coupling &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)=0
~ChainIkSolverPos_NR_JL_coupling()
ChainIkSolverVel & iksolver
ChainFkSolverPos & fksolver
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)