81 static const char rcsid[] =
"$Id: kinemat.cpp,v 1.31 2004/08/16 00:37:53 gourdeau Exp $";
88 using namespace NEWMAT;
99 kine(Rot,pos,dof+fix);
110 if(j < 1 || j > dof+fix) error(
"j must be 1 <= j <= dof+fix");
114 for (
int i = 2; i <= j; i++) {
115 pos = pos + Rot*links[i].p;
116 Rot = Rot*links[i].R;
125 thomo = kine(dof+fix);
158 error(
"j must be 1 <= j <= dof");
160 kine_pd(Rot, pos, pos_dot, j);
162 temp.SubMatrix(1,3,1,3) = Rot;
201 Matrix jacob_inv_DLS, U, V;
203 SVD(jacobian(ref), Q, U, V);
206 jacob_inv_DLS = V*Q.
i()*U.
t();
209 Q(6,6) += (1 - pow(Q(6,6)/eps,2))*lambda_max*lambda_max;
210 jacob_inv_DLS = V*Q.
i()*U.
t();
214 return(jacob_inv_DLS);
231 error(
"j must be 1 <= j <= dof");
233 if( (pos.Nrows()!=3) || (pos.Ncols()!=1) )
235 if( (pos_dot.Nrows()!=3) || (pos_dot.Ncols()!=1) )
240 for(
int i = 1; i <= j; i++)
242 R[i] = R[i-1]*links[i].R;
243 pos = pos + R[i-1]*links[i].p;
244 pos_dot = pos_dot +
CrossProduct(R[i]*w[i], R[i-1]*links[i].p);
295 if(i < 1 || i > dof) error(
"i must be 1 <= i <= dof");
296 if(links[i].get_immobile()) {
301 }
else if(links[i].get_joint_type() == 0) {
308 for(j = 1; j < i; j++) {
309 dRot = dRot*links[j].R;
312 for(j = 1; j <= 3; j++) {
314 dR(j,2) = -dRot(j,1);
316 for(j = i+1; j <= dof; j++) {
317 p2 = p2 + R2*links[j].p;
328 for(j = i-1; j >= 1; j--) {
345 dTdqi(dRot, dpos, i);
403 const int adof=get_available_dof(endlink);
407 if(ref < 0 || ref > dof) error(
"invalid referential");
409 for(i = 1; i <= dof; i++) {
410 R[i] = R[i-1]*links[i].R;
411 p[i] = p[i-1]+R[i-1]*links[i].p;
414 for(i=1,j=1; j <= adof; i++) {
415 if(links[i].get_immobile())
417 if(links[i].get_joint_type() == 0) {
418 temp(1,1) = R[i-1](1,3);
419 temp(2,1) = R[i-1](2,3);
420 temp(3,1) = R[i-1](3,3);
423 jac(1,j) = temp(1,1);
424 jac(2,j) = temp(2,1);
425 jac(3,j) = temp(3,1);
426 jac(4,j) = R[i-1](1,3);
427 jac(5,j) = R[i-1](2,3);
428 jac(6,j) = R[i-1](3,3);
430 jac(1,j) = R[i-1](1,3);
431 jac(2,j) = R[i-1](2,3);
432 jac(3,j) = R[i-1](3,3);
433 jac(4,j) = jac(5,j) = jac(6,j) = 0.0;
443 Rot = ((RT & zeros) | (zeros & RT));
499 const int adof=get_available_dof();
503 if(ref < 0 || ref > dof)
504 error(
"invalid referential");
506 for(i = 1; i <= dof; i++)
508 R[i] = R[i-1]*links[i].R;
509 p[i] = p[i-1] + R[i-1]*links[i].p;
510 pp[i] = pp[i-1] +
CrossProduct(R[i]*w[i], R[i-1]*links[i].p);
513 for(i=1,j=1; j <= adof; i++) {
514 if(links[i].get_immobile())
516 if(links[i].get_joint_type() == 0)
519 ppr = pp[dof]-pp[i-1];
524 jacdot(4,j) = temp(1);
525 jacdot(5,j) = temp(2);
526 jacdot(6,j) = temp(3);
528 jacdot(1,j) = temp(1);
529 jacdot(2,j) = temp(2);
530 jacdot(3,j) = temp(3);
533 jacdot(1,j) = jacdot(2,j) = jacdot(3,j) =
534 jacdot(4,j) = jacdot(5,j) = jacdot(6,j) = 0.0;
543 Rot = ((RT & zeros) | (zeros & RT));
547 jacdot.
Release();
return jacdot;
563 if(j < 1 || j > dof+fix)
564 error(
"j must be 1 <= j <= dof+fix");
566 if( (pos.Nrows()!=3) || (pos.Ncols()!=1) )
568 if( (pos_dot.Nrows()!=3) || (pos_dot.Ncols()!=1) )
573 for(
int i = 1; i <= j; i++)
575 pos = pos + R[i-1]*links[i].p;
576 pos_dot = pos_dot + R[i-1]*
CrossProduct(w[i-1], links[i].p);
577 R[i] = R[i-1]*links[i].R;
620 if(i < 1 || i > dof) error(
"i must be 1 <= i <= dof");
621 if(links[i].get_immobile()) {
626 }
else if(links[i].get_joint_type() == 0) {
627 Matrix dR(3,3), R2(3,3), p2(3,1);
631 for(j = 1; j <= i; j++) {
632 dRot = dRot*links[j].R;
635 for(j = 1; j <= 3; j++) {
637 dR(j,2) = -dRot(j,1);
646 for(j = i+1; j <= dof; j++) {
647 p2 = p2 + R2*links[j].p;
658 for(j = i; j >= 1; j--) {
675 dTdqi(dRot, dpos, i);
690 const int adof=get_available_dof(endlink);
694 if(ref < 0 || ref > dof+fix)
695 error(
"invalid referential");
697 for(i = 1; i <= dof+fix; i++) {
698 R[i] = R[i-1]*links[i].R;
699 p[i] = p[i-1] + R[i-1]*links[i].p;
702 for(i=1,j=1; j <= adof; i++) {
703 if(links[i].get_immobile())
705 if(links[i].get_joint_type() == 0){
709 pr = p[dof+fix]-p[i];
714 jac(4,j) = R[i](1,3);
715 jac(5,j) = R[i](2,3);
716 jac(6,j) = R[i](3,3);
718 jac(1,j) = R[i](1,3);
719 jac(2,j) = R[i](2,3);
720 jac(3,j) = R[i](3,3);
721 jac(4,j) = jac(5,j) = jac(6,j) = 0.0;
730 Rot = ((RT & zeros) | (zeros & RT));
744 const int adof=get_available_dof();
748 if(ref < 0 || ref > dof+fix)
749 error(
"invalid referential");
751 for(i = 1; i <= dof+fix; i++)
753 R[i] = R[i-1]*links[i].R;
754 p[i] = p[i-1] + R[i-1]*links[i].p;
755 pp[i] = pp[i-1] + R[i-1]*
CrossProduct(w[i-1], links[i].p);
758 for(i=1,j=1; j <= adof; i++) {
759 if(links[i].get_immobile())
761 if(links[i].get_joint_type() == 0)
763 pr = p[dof+fix]-p[i];
764 ppr = pp[dof+fix]-pp[i];
770 jacdot(4,j) = temp(1);
771 jacdot(5,j) = temp(2);
772 jacdot(6,j) = temp(3);
775 jacdot(1,j) = temp(1);
776 jacdot(2,j) = temp(2);
777 jacdot(3,j) = temp(3);
780 jacdot(1,j) = jacdot(2,j) = jacdot(3,j) =
781 jacdot(4,j) = jacdot(5,j) = jacdot(6,j) = 0.0;
790 Rot = ((RT & zeros) | (zeros & RT));
794 jacdot.
Release();
return jacdot;
810 if(j < 1 || j > dof+fix)
811 error(
"j must be 1 <= j <= dof+fix");
813 if( (pos.Nrows()!=3) || (pos.Ncols()!=1) )
815 if( (pos_dot.Nrows()!=3) || (pos_dot.Ncols()!=1) )
820 for(
int i = 1; i <= j; i++)
822 pos = pos + R[i-1]*links[i].p;
823 pos_dot = pos_dot + R[i-1]*
CrossProduct(w[i-1], links[i].p);
824 R[i] = R[i-1]*links[i].R;
843 if(i < 1 || i > dof) error(
"i must be 1 <= i <= dof");
844 if(links[i].get_immobile()) {
849 }
else if(links[i].get_joint_type() == 0) {
850 Matrix dR(3,3), R2, p2(3,1);
854 for(j = 1; j <= i; j++) {
855 dRot = dRot*links[j].R;
858 for(j = 1; j <= 3; j++) {
860 dR(j,2) = -dRot(j,1);
869 for(j = i+1; j <= dof; j++) {
870 p2 = p2 + R2*links[j].p;
881 for(j = i; j >= 1; j--) {
898 dTdqi(dRot, dpos, i);
913 const int adof=get_available_dof(endlink);
917 if(ref < 0 || ref > dof+fix)
918 error(
"invalid referential");
920 for(i = 1; i <= dof+fix; i++) {
921 R[i] = R[i-1]*links[i].R;
922 p[i] = p[i-1] + R[i-1]*links[i].p;
925 for(i=1,j=1; j<=adof; i++) {
926 if(links[i].get_immobile())
928 if(links[i].get_joint_type() == 0){
933 pr = p[dof+fix]-p[i];
938 jac(4,j) = R[i](1,3);
939 jac(5,j) = R[i](2,3);
940 jac(6,j) = R[i](3,3);
942 jac(1,j) = R[i](1,3);
943 jac(2,j) = R[i](2,3);
944 jac(3,j) = R[i](3,3);
945 jac(4,j) = jac(5,j) = jac(6,j) = 0.0;
954 Rot = ((RT & zeros) | (zeros & RT));
969 const int adof=get_available_dof();
973 if(ref < 0 || ref > dof+fix)
974 error(
"invalid referential");
976 for(i = 1; i <= dof+fix; i++)
978 R[i] = R[i-1]*links[i].R;
979 p[i] = p[i-1] + R[i-1]*links[i].p;
980 pp[i] = pp[i-1] + R[i-1]*
CrossProduct(w[i-1], links[i].p);
983 for(i=1,j=1; j <= dof; i++) {
984 if(links[i].get_immobile())
986 if(links[i].get_joint_type() == 0)
988 pr = p[dof+fix]-p[i];
989 ppr = pp[dof+fix]-pp[i];
995 jacdot(4,j) = temp(1);
996 jacdot(5,j) = temp(2);
997 jacdot(6,j) = temp(3);
1000 jacdot(1,j) = temp(1);
1001 jacdot(2,j) = temp(2);
1002 jacdot(3,j) = temp(3);
1005 jacdot(1,j) = jacdot(2,j) = jacdot(3,j) =
1006 jacdot(4,j) = jacdot(5,j) = jacdot(6,j) = 0.0;
1015 Rot = ((RT & zeros) | (zeros & RT));
1016 jacdot = Rot*jacdot;
1019 jacdot.
Release();
return jacdot;
1022 #ifdef use_namespace
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
virtual void kine_pd(Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref) const
Direct kinematics with velocity.
Robots class definitions.
ReturnMatrix kine(void) const
Return the end effector direct kinematics transform matrix.
virtual void dTdqi(Matrix &dRot, ColumnVector &dp, const int i)
Partial derivative of the robot position (homogeneous transf.)
TransposedMatrix t() const
virtual ReturnMatrix jacobian_dot(const int ref=0) const
Jacobian derivative of mobile joints expressed at frame ref.
Matrix CrossProduct(const Matrix &A, const Matrix &B)
void SVD(const Matrix &, DiagonalMatrix &, Matrix &, Matrix &, bool=true, bool=true)
The usual rectangular matrix.
virtual ReturnMatrix jacobian_dot(const int ref=0) const
Jacobian derivative of mobile joints expressed at frame ref.
virtual void dTdqi(Matrix &dRot, ColumnVector &dp, const int i)
Partial derivative of the robot position (homogeneous transf.)
virtual void kine_pd(Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref) const
Direct kinematics with velocity.
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
static const char rcsid[]
RCS/CVS version.
ReturnMatrix kine_pd(const int ref=0) const
Direct kinematics with velocity.
virtual ReturnMatrix jacobian_dot(const int ref=0) const
Jacobian derivative of mobile joints expressed at frame ref.
GetSubMatrix SubMatrix(int fr, int lr, int fc, int lc) const
ReturnMatrix jacobian_DLS_inv(const double eps, const double lambda_max, const int ref=0) const
Inverse Jacobian based on damped least squares inverse.
virtual void kine_pd(Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref=0) const
Direct kinematics with velocity.
Real threebythreeident[]
Used to initialize a matrix.
Real fourbyfourident[]
Used to initialize a matrix.
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
virtual void dTdqi(Matrix &dRot, ColumnVector &dp, const int i)
Partial derivative of the robot position (homogeneous transf.)