42 static const char rcsid[] =
"$Id: controller.cpp,v 1.3 2005/11/15 19:06:13 gourdeau Exp $";
50 using namespace NEWMAT;
109 cerr <<
"Impedance::set_Mp: wrong size for input matrix Mp" << endl;
123 if( (i < 0) || (i > 3) )
125 cerr <<
"Impedance::set_Mp: index i out of bound" << endl;
142 cerr <<
"Impedance::set_Dp: input matrix Dp of wrong size" << endl;
156 if( (i < 0) || (i > 3) )
158 cerr <<
"Impedance::set_Dp: index i out of bound" << endl;
175 cerr <<
"Impedance::set_Kp: wrong size for input matrix Kp" << endl;
189 if( (i < 0) || (i > 3) )
191 cerr <<
"Impedance::set_Mp: index i out of bound" << endl;
208 cerr <<
"Impedance::set_Mo: wrong size input matrix Mo" << endl;
222 if( (i < 0) || (i > 3) )
224 cerr <<
"Impedance::set_Mo: index i out of bound" << endl;
238 if( Do_.
Nrows() != 3)
241 cerr <<
"Impedance::set_Do: wrong size input matrix Do" << endl;
255 if( (i < 0) || (i > 3) )
257 cerr <<
"Impedance::set_Do: index i out of bound" << endl;
274 cerr <<
"Impedance::set_Ko: wrong size for input matrix Ko" << endl;
288 if( (i < 0) || (i > 3) )
290 cerr <<
"Impedance::set_Ko: index i out of bound" << endl;
331 cerr <<
"Impedance::control: wrong size for input vector pdpp" << endl;
336 cerr <<
"Impedance::control: wrong size for input vector pdp" << endl;
341 cerr <<
"Impedance::control: wrong size for input vector pd" << endl;
346 cerr <<
"Impedance::control: wrong size for input vector wdp" << endl;
351 cerr <<
"Impedance::control: wrong size for input vector wd" << endl;
356 cerr <<
"Impedance::control: wrong size for input vector f" << endl;
361 cerr <<
"Impedance::control: wrong size for input vector f" << endl;
365 static bool first=
true;
375 if(qc.dot_prod(qd) < 0)
386 pcpp = pdpp + Mp.
i()*(f - Dp*pcdp - Kp*pcd);
387 pcp = pcp_prev +
Integ_Trap(pcpp, pcpp_prev, dt);
395 wcp = wdp + Mo.
i()*(n - Do*wcd - Ko_prime*qcd.v());
410 Kvp = Kpp = Kvo = Kpo = 0;
421 quat_v_error = zero3;
443 quat_v_error = zero3;
474 const Quaternion & quatd,
const short link_pc,
488 robot.
kine_pd(Rot, p, pp, link_pc);
496 quat_v_error = quate.
s()*quat.v() - quat.s()*quate.
v() +
499 a.SubMatrix(1,3,1,1) = pdpp + Kvp*(pdp-pp) + Kpp*(pd-p);
500 a.SubMatrix(4,6,1,1) = wdp + Kvo*(wd-Rot*robot.
w[robot.
get_dof()]) +
505 return robot.
torque(robot.
get_q(),qp, qpp, zero3, zero3);
543 if(qd.
Nrows() != dof)
546 cerr <<
"Computed_torque_methode::torque_cmd: wrong size for input vector qd" << endl;
550 if(qpd.
Nrows() != dof)
553 cerr <<
"Computed_torque_methode::torque_cmd: wrong size for input vector qpd" << endl;
557 if(qppd.
Nrows() != dof)
560 cerr <<
"Computed_torque_methode::torque_cmd: wrong size for input vector qppd" << endl;
567 qpp = Kp*(qd-q) + Kd*(qpd-qp) + qppd;
568 return robot.
torque(q, qp, qpp, zero3, zero3);
577 if(Kd_.
Nrows() != dof)
580 cerr <<
"Computed_torque_method::set_kd: wrong size for input matrix Kd." << endl;
594 if(Kp_.
Nrows() != dof)
597 cerr <<
"Computed_torque_method::set_kp: wrong size for input matrix Kp." << endl;
637 if(qd.
Nrows() != dof)
640 cerr <<
"Proportional_Derivative::torque_cmd: wrong size for input vector qd" << endl;
643 if(qpd.
Nrows() != dof)
646 cerr <<
"Proportional_Derivative::torque_cmd: wrong size for input vector qpd" << endl;
652 tau = Kp*(qd-q) + Kd*(qpd-qp);
663 if(Kd_.
Nrows() != dof)
666 cerr <<
"Proportional_Derivative::set_kd: wrong size for input matrix Kd." << endl;
680 if(Kp_.
Nrows() != dof)
683 cerr <<
"Computed_torque_method::set_kp: wrong size for input matrix Kp." << endl;
Quaternion class definition.
short set_Do(const DiagonalMatrix &Do_)
Assign the rotational impedance damping matrix .
Resolved_acc(const short dof=1)
Constructor.
ReturnMatrix v() const
Return vector part.
ReturnMatrix Integ_Trap(const ColumnVector &present, ColumnVector &past, const Real dt)
Trapezoidal integration.
ReturnMatrix get_qp(void) const
Return the joint velocity vector.
short set_Kp(const DiagonalMatrix &Kp_)
Assign the translational impedance stifness matrix .
int get_dof() const
Return dof.
ReturnMatrix torque_cmd(Robot_basic &robot, const ColumnVector &pdpp, const ColumnVector &pdp, const ColumnVector &pd, const ColumnVector &wdp, const ColumnVector &wd, const Quaternion &qd, const short link_pc, const Real dt)
Output torque.
#define WRONG_SIZE
Return value when input vectors or matrix don't have the right size.
ReturnMatrix x_prod_matrix(const ColumnVector &x)
Cross product matrix.
ReturnMatrix torque_cmd(Robot_basic &robot, const ColumnVector &qd, const ColumnVector &qpd, const ColumnVector &qppd)
Output torque.
void set_Kvp(const Real Kvp)
Assign the gain .
short set_Kp(const DiagonalMatrix &Kp)
Assign the position error gain matrix .
ReturnMatrix torque_cmd(Robot_basic &robot, const ColumnVector &qd, const ColumnVector &qpd)
Output torque.
short Integ_quat(Quaternion &dquat_present, Quaternion &dquat_past, Quaternion &quat, const Real dt)
Trapezoidal quaternion integration.
Real s() const
Return scalar part.
static const char rcsid[]
RCS/CVS version.
void set_Kpo(const Real Kpo)
Assign the gain .
short set_Kd(const DiagonalMatrix &Kd)
Assign the velocity error gain matrix .
short set_Mp(const DiagonalMatrix &Mp_)
Assign the translational impedance inertia matrix .
virtual ReturnMatrix jacobian_dot(const int ref=0) const =0
short set_Mo(const DiagonalMatrix &Mo_)
Assign the rotational impedance inertia matrix .
Virtual base robot class.
short set_Kp(const DiagonalMatrix &Kp)
Assign the position error gain matrix .
short set_Kd(const DiagonalMatrix &Kd)
Assign the velocity error gain matrix .
The usual rectangular matrix.
Quaternion dot(const ColumnVector &w, const short sign) const
Quaternion time derivative.
Header file for controller class definitions.
void set_Kvo(const Real Kvo)
Assign the gain .
FloatVector FloatVector * a
Real dot_prod(const Quaternion &q) const
Quaternion dot product.
ReturnMatrix kine_pd(const int ref=0) const
Direct kinematics with velocity.
void kine(Matrix &Rot, ColumnVector &pos) const
Direct kinematics at end effector.
Quaternion i() const
Quaternion inverse. where and are the quaternion conjugate and the quaternion norm respectively...
ReturnMatrix jacobian_DLS_inv(const double eps, const double lambda_max, const int ref=0) const
Inverse Jacobian based on damped least squares inverse.
short control(const ColumnVector &pdpp, const ColumnVector &pdp, const ColumnVector &pd, const ColumnVector &wdp, const ColumnVector &wd, const Quaternion &qd, const ColumnVector &f, const ColumnVector &n, const Real dt)
Generation of a compliance trajectory.
virtual ReturnMatrix torque(const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp)=0
Computed_torque_method(const short dof=1)
Constructor.
void set_Kpp(const Real Kpp)
Assign the gain .
Proportional_Derivative(const short dof=1)
Constructor.
short set_Dp(const DiagonalMatrix &Dp_)
Assign the translational impedance damping matrix .
Real get_q(const int i) const
short set_Ko(const DiagonalMatrix &Ko_)
Assign the rotational impedance stifness matrix .