/** * @brief Description: Algorithm module of robotics, according to the * book[modern robotics : mechanics, planning, and control]. * @file: RobotAlgorithmModule.c * @author: Brian * @date: 2019/03/01 12:23 * Copyright(c) 2019 Brian. All rights reserved. * * Contact https://blog.csdn.net/Galaxy_Robot * @note: *@warning: */ #include "RobotAlgorithmModule.h" #include #include #include #include /** *@brief Description:use GrublersFormula calculate The number of degrees of * freedom of a mechanism with links and joints. *@param[in] N the number of links( including the ground ). *@param[in] m the number of degrees of freedom of a rigid body. * (m = 3 for planar mechanisms and m = 6 for spatial mechanisms). *@param[in] J the number of joints. *@param[in] f the number of freedoms provided by each joint.. *@return The number of degrees of freedom of a mechanism *@note: This formula holds only if all joint constraints are independent. * If they are not independent then the formula provides a lower * bound on the number of degrees of freedom. *@warning: */ int GrublersFormula(int m, int N, int J, int *f) { int i; int dof; int c = 0; for (i=1;i<=J;i++) { c = c + f[i-1]; } dof = m*(N - 1 - J) + c; return dof; } /** *@brief Description: Make matrix b equal to matrix a. *@param[in] a a 3 x 3 matrix. *@param[out] b result,b=a. *@return No return value. *@note: *@warning: */ void Matrix3Equal(double a[][3], double b[][3]) { int i; int j; for (i = 0; i < 3; i++) { for (j = 0; j < 3; j++) { b[i][j] = a[i][j]; } } return; } /** *@brief Description: Make matrix b equal to matrix a. *@param[in] a a 4 x 4 matrix. *@param[out] b result,b=a. *@return No return value. *@note: *@warning: */ void Matrix4Equal(double a[][4], double b[][4]) { int i; int j; for (i = 0; i < 4; i++) { for (j = 0; j < 4; j++) { b[i][j] = a[i][j]; } } return; } /** *@brief Description:Calculate a 3 x 3 matrix add a 3 x 3 matrix. *@param[in] a a 3 x 3 matrix. *@param[in] b a 3 x 3 matrix. *@param[out] c result of a+b. *@return No return value. *@note: *@warning: */ void Matrix3Add(double a[][3], double b[][3], double c[][3]) { int i; int j; for (i = 0; i < 3; i++) { for (j = 0; j < 3; j++) { c[i][j] = a[i][j] + b[i][j]; } } return; } /** *@brief Description:Calculate a 4 x 4 matrix add a 4 x 4 matrix. *@param[in] a a 4 x 4 matrix. *@param[in] b a 4 x 4 matrix. *@param[out] c result of a+b. *@return No return value. *@note: *@warning: */ void Matrix4Add(double a[][4], double b[][4], double c[][4]) { int i; int j; for (i = 0; i < 4; i++) { for (j = 0; j < 4; j++) { c[i][j] = a[i][j] + b[i][j]; } } return; } /** *@brief Description:Calculate a 3 x 3 matrix Subtract a 3 x 3 matrix. *@param[in] a a 3 x 3 matrix. *@param[in] b a 3 x 3 matrix. *@param[out] c result of a-b. *@return No return value. *@note: *@warning: */ void Matrix3Sub(double a[][3], double b[][3], double c[][3]) { int i; int j; for (i = 0; i < 3; i++) { for (j = 0; j < 3; j++) { c[i][j] = a[i][j] - b[i][j]; } } return; } /** *@brief Description:Calculate a 4 x 4 matrix Subtract a 4 x 4 matrix. *@param[in] a a 4 x 4 matrix. *@param[in] b a 4 x 4 matrix. *@param[out] c result of a-b. *@return No return value. *@note: *@warning: */ void Matrix4Sub(double a[][4], double b[][4], double c[][4]) { int i; int j; for (i = 0; i < 4; i++) { for (j = 0; j < 4; j++) { c[i][j] = a[i][j] - b[i][j]; } } return; } /** *@brief Description: Calculate two 3 x 3 matrix multiplication. *@param[in] a a 3 x 3 matrix. *@param[in] b a 3 x 3 matrix. *@param[out] c result of a*b. *@return No return value. *@note: *@warning: */ void Matrix3Mult(double a[][3],double b[][3],double c[][3]) { int i; int j; int k; for (i=0;i<3;i++) { for (j=0;j<3;j++) { c[i][j] = 0.0; for (k=0;k<3;k++) { c[i][j] = c[i][j] + a[i][k] * b[k][j]; } } } return; } /** *@brief Description: Calculate two 4 x 4 matrix multiplication. *@param[in] a a 4 x 4 matrix. *@param[in] b a 4 x 4 matrix. *@param[out] c result of a*b. *@return No return value. *@note: *@warning: */ void Matrix4Mult(double a[][4], double b[][4], double c[][4]) { int i; int j; int k; for (i = 0; i < 4; i++) { for (j = 0; j < 4; j++) { c[i][j] = 0.0; for (k = 0; k < 4; k++) { c[i][j] = c[i][j] + a[i][k] * b[k][j]; } } } return; } /** *@brief Description: Calculate 3 x 3 matrix multiply a value. *@param[in] a a 3 x 3 matrix. *@param[in] Value a scalar value. *@param[out] c result of a*Value. *@return No return value. *@note: *@warning: */ void Matrix3MultValue(double a[][3], double Value, double c[][3]) { int i; int j; for (i=0;i<3;i++) { for (j=0;j<3;j++) { c[i][j] = a[i][j] * Value; } } return; } /** *@brief Description: Calculate 4 x 4 matrix multiply a value. *@param[in] a a 4 x 4 matrix. *@param[in] Value a scalar value. *@param[out] c result of a*Value. *@return No return value. *@note: *@warning: */ void Matrix4MultValue(double a[][4], double Value, double c[][4]) { int i; int j; for (i = 0; i < 4; i++) { for (j = 0; j < 4; j++) { c[i][j] = a[i][j] * Value; } } return; } /** *@brief Description:Computes the result of a 3 x 3 Matrix multiply a 3-vector. *@param[in] R a 3 x 3 Matrix. *@param[in] vec1 an input of 3-vector. *@param[out] vec2 the output result of 3-vector. *@return No return value. *@note: *@warning: */ void Matrix3MultVec(double R[3][3], double vec1[3], double vec2[3]) { int i; int j; for (i=0;i<3;i++) { vec2[i] = 0; for (j=0;j<3;j++) { vec2[i] = vec2[i] + R[i][j] * vec1[j]; } } return; } /** *@brief Description:Computes a 3-vector add a 3-vector. *@param[in] vec1 a 3-vector. *@param[in] vec2 a 3-vector. *@param[out] vec3 result of vec1 + vec2; *@return No return value. *@note: *@warning: */ void Vec3Add(double vec1[3], double vec2[3], double vec3[3]) { vec3[0] = vec1[0] + vec2[0]; vec3[1] = vec1[1] + vec2[1]; vec3[2] = vec1[2] + vec2[2]; return; } /** *@brief Description:Computes result of two 3-vector cross product. *@param[in] vec1 a first 3-vector. *@param[in] vec2 a first 3-vector. *@param[out] vec3 result of vec1 cross product vec2. *@return No return value. *@note: *@warning: */ void Vec3Cross(double vec1[3],double vec2[3],double vec3[3]) { vec3[0] = vec1[1] * vec2[2] - vec2[1] * vec1[2]; vec3[1] = -(vec1[0] * vec2[2] - vec2[0] * vec1[2]); vec3[2] = vec1[0] * vec2[1] - vec2[0] * vec1[1]; return; } /** *@brief Description:Computes a 3-vector multiply a scalar value. *@param[in] vec1 a 3-vector. *@param[in] value a scalar value. *@param[out] vec2 result of vec1 * value. *@return No return value. *@note: *@warning: */ void Vec3MultValue(double vec1[3], double value, double vec2[3]) { vec2[0] = vec1[0] * value; vec2[1] = vec1[1] * value; vec2[2] = vec1[2] * value; return; } /** *@brief Description: Computes the norm of a 3-vector. *@param[in] vec an input 3-vector. *@return the norm of a an input 3-vector. *@note: *@warning: */ double Vec3Norm2(double vec[3]) { return sqrt(vec[0] * vec[0] + vec[1] * vec[1] + vec[2] * vec[2]); } /** *@brief Description: Computes the 2-norm of a n-vector. *@param[in] n dimension of vector. *@param[in] vec an input n-vector. *@return the norm of a an input 3-vector. *@note: *@warning: */ double VecNorm2(int n,double *vec) { int i; double tmp=0.0; for (i=0;i= ZERO_VALUE) { omg[0] = 1.0 / sqrt(2 * (1.0 + R[2][2]))*R[0][2]; omg[1] = 1.0 / sqrt(2 * (1.0 + R[2][2]))*R[1][2]; omg[2] = 1.0 / sqrt(2 * (1.0 + R[2][2]))*(1.0 + R[2][2]); } else if ((1.0+R[1][1]>= ZERO_VALUE)) { omg[0] = 1.0 / sqrt(2 * (1.0 + R[1][1]))*R[0][1]; omg[1] = 1.0 / sqrt(2 * (1.0 + R[1][1]))*(1.0 + R[1][1]); omg[2] = 1.0 / sqrt(2 * (1.0 + R[1][1]))*R[2][1]; } else { omg[0] = 1.0 / sqrt(2 * (1.0 + R[0][0]))*(1.0 + R[0][0]); omg[1] = 1.0 / sqrt(2 * (1.0 + R[0][0]))*R[1][0]; omg[2] = 1.0 / sqrt(2 * (1.0 + R[0][0]))*R[2][0]; } omg[0] = PI*omg[0]; omg[1] = PI*omg[1]; omg[2] = PI*omg[2]; VecToso3(omg, so3Mat); } else { int i; int j; double theta = acos(acosinput); for (i=0;i<3;i++) { for (j=0;j<3;j++) { so3Mat[i][j] = 1.0 / (2.0*sin(theta))*(R[i][j] - R[j][i])*theta; } } } return; } /** *@brief Description:Builds the homogeneous transformation matrix T corresponding to a rotation * matrix R in SO(3) and a position vector p in R3. *@param[in] R a rotation matrix R in SO(3). *@param[in] p a position vector p in R3. *@param[out] T the homogeneous transformation matrix T. *@return No return value. *@note: *@warning: */ void RpToTrans(double R[3][3], double p[3], double T[4][4]) { int i; int j; for (i=0;i<3;i++) { for (j=0;j<3;j++) { T[i][j] = R[i][j]; } } T[0][3] = p[0]; T[1][3] = p[1]; T[2][3] = p[2]; T[3][0] = 0.0; T[3][1] = 0.0; T[3][2] = 0.0; T[3][3] = 1.0; return; } /** *@brief Description: Extracts the rotation matrix R and position vector p from a homogeneous transformation matrix T. *@param[in] T a homogeneous transformation matrix. *@param[out] R the rotation matrix. *@param[out] p position vector. *@return No return value. *@note: *@waring: */ void TransToRp(double T[4][4], double R[3][3], double p[3]) { int i; int j; for (i=0;i<3;i++) { for (j=0;j<3;j++) { R[i][j] = T[i][j]; } } p[0] = T[0][3]; p[1] = T[1][3]; p[2] = T[2][3]; return; } /** *@brief Description:Computes the inverse of a homogeneous transformation matrix T. *@param[in] T a homogeneous transformation matrix. *@param[out] InvT the inverse of T. *@return No return value. *@note: *@warning: */ void TransInv(double T[4][4],double InvT[4][4]) { double R[3][3]; double InvR[3][3]; double p[3]; double p2[3]; TransToRp(T, R, p); RotInv(R, InvR); Matrix3MultValue(InvR, -1.0, R); Matrix3MultVec(R, p, p2); RpToTrans(InvR, p2, InvT); return; } /** *@brief Description:Computes the se(3) matrix corresponding to a 6-vector twist V. *@param[in] V a 6-vector twist V. *@param[out] se3Mat the se(3) matrix. *@return No return value. *@note: *@warning: */ void VecTose3(double V[6], double se3Mat[4][4]) { double so3Mat[3][3]; double omg[3]; int i; int j; omg[0] = V[0]; omg[1] = V[1]; omg[2] = V[2]; VecToso3(omg, so3Mat); for (i=0;i<3;i++) { for (j=0;j<3;j++) { se3Mat[i][j] = so3Mat[i][j]; } } se3Mat[0][3] = V[3]; se3Mat[1][3] = V[4]; se3Mat[2][3] = V[5]; se3Mat[3][0] = 0.0; se3Mat[3][1] = 0.0; se3Mat[3][2] = 0.0; se3Mat[3][3] = 0.0; return; } /** *@brief Description:Computes the 6-vector twist corresponding to an se(3) matrix se3mat. *@param[in] se3Mat an se(3) matrix. *@param[out] V he 6-vector twist. *@return No return value. *@note: *@warning: */ void se3ToVec(double se3Mat[4][4],double V[6]) { V[0] = se3Mat[2][1]; V[1] = se3Mat[0][2]; V[2] = se3Mat[1][0]; V[3] = se3Mat[0][3]; V[4] = se3Mat[1][3]; V[5] = se3Mat[2][3]; return; } /** *@brief Description:Computes the 6 x 6 adjoint representation [AdT ] of the homogeneous transformation matrix T. *@param[in] T a homogeneous transformation matrix. *@param[out] AdT the 6 x 6 adjoint representation [AdT ]. *@return No return value. *@note: *@warning: */ void Adjoint(double T[4][4], double AdT[6][6]) { double R[3][3]; double p[3]; double so3Mat[3][3]; int i; int j; TransToRp(T, R, p); VecToso3(p, so3Mat); for (i=0;i<3;i++) { for (j=0;j<3;j++) { AdT[i][j] = R[i][j]; } } for (i = 0; i < 3; i++) { for (j = 3; j < 6; j++) { AdT[i][j] = 0.0; } } for (i=3;i<6;i++) { for (j = 3; j < 6; j++) { AdT[i][j] = R[i-3][j-3]; } } double mat[3][3]; Matrix3Mult(so3Mat, R, mat); for (i = 3; i < 6; i++) { for (j = 0; j < 3; j++) { AdT[i][j] = mat[i-3][j]; } } return; } /** *@brief Description: Computes a normalized screw axis representation S of a screw described by * a unit vector s in the direction of the screw axis, located at the point q, with pitch h. *@param[in] q a point lying on the screw axis. *@param[in] s a unit vector in the direction of the screw axis. *@param[in] h the pitch of the screw axis. *@param[in] S a normalized screw axis representation. *@return No return value. *@note: *@warning: */ void ScrewToAxis(double q[3], double s[3], double h,double S[6]) { double v[3]; double temp[3]; Vec3Cross(s, q, temp); Vec3MultValue(temp, -1.0, temp); Vec3MultValue(s, h, v); Vec3Add(v, temp, v); S[0] = s[0]; S[1] = s[1]; S[2] = s[2]; S[3] = v[0]; S[4] = v[1]; S[5] = v[2]; return; } /** *@brief Description: Extracts the normalized screw axis S and the distance traveled along the screw theta from the 6-vector of exponential coordinates S*theta. *@param[in] expc6 the 6-vector of exponential coordinates. *@param[out] S the normalized screw axis. *@param[out] theta the distance traveled along the screw. *@return No return value. *@note: *@warning: */ void AxisAng6(double expc6[6],double S[6],double *theta) { *theta = Vec3Norm2(expc6); if (*theta=0;i--) { for (l=0;l<6;l++) { V[l] = Slist[l*JointNum+i];//get each column of Slist. } VecTose3(V, se3mat); for (j=0;j<4;j++) { for (k=0;k<4;k++) { se3mat[j][k] = se3mat[j][k] * thetalist[i]; } } MatrixExp6(se3mat, exp6); Matrix4Mult(exp6, T, T2); Matrix4Equal(T2, T); } return ; } /** *@brief Description:Computes the end-effector frame given the zero position of the end-effector M, * the list of joint screws Blist expressed in the end-effector frame, and the list of joint values thetalist. *@param[in] M the zero position of the end-effector expressed in the end-effector frame. *@param[in] JointNum the number of joints. *@param[in] Blist the list of joint screws Slist expressed in the end-effector frame. * in the format of a matrix with the screw axes as the column. *@param[in] thetalist the list of joint values. *@param[out] T the end-effector frame expressed in the end-effector frame. *@return No return value. *@note: when Blist is a matrix ,make sure that columns number of Slist is equal to JointNum, * rows number of Slist 6 .The function call should be written as * FKinBody(...,(double *)Blist,...). *@warning: */ void FKinBody(double M[4][4], int JointNum, double *Blist, double thetalist[], double T[4][4]) { int i, j, k, l; double se3mat[4][4]; double T2[4][4]; double exp6[4][4]; double V[6]; Matrix4Equal(M, T); for (i = 0; i < JointNum ; i++) { for (l = 0; l < 6; l++) { V[l] = Blist[l*JointNum + i];//get each column of Slist. } VecTose3(V, se3mat); for (j = 0; j < 4; j++) { for (k = 0; k < 4; k++) { se3mat[j][k] = se3mat[j][k] * thetalist[i]; } } MatrixExp6(se3mat, exp6); Matrix4Mult(T, exp6, T2); Matrix4Equal(T2, T); } return ; } /** *@brief Description: Computes the body Jacobian Jb(theta) in 6×n given a list of joint screws Bi expressed in the body frame and a list of joint angles. *@param[in] Blist The joint screw axes in the end - effector frame when the manipulator is * at the home position, in the format of a matrix with the screw axes as the row. *@param[in] thetalist A list of joint coordinates. *@param[out] Jb Body Jacobian matrix. *@return No return value. *@note: when Blist and Jb are matrixes ,make sure that columns number of Slist or Jb is equal to JointNum, * rows number of Slist or Jb is 6 .The function call should be written as * JacobianSpace(JointNum,(double *)Slist,thetalist,(double *)Jb). *@warning: */ void JacobianBody(int JointNum,double *Blist, double *thetalist,double *Jb) { int i; int j; int k; double T1[4][4]; double T2[4][4]; double se3mat[4][4]; double V[6]; double AdT[6][6]; double T[4][4] = { 1,0,0,0, 0,1,0,0, 0,0,1,0, 0,0,0,1 }; //Fist column of Jbn. for (i=0;i<6;i++) { Jb[i*JointNum+JointNum -1] = Blist[i*JointNum + JointNum-1]; } //Jbi for i=n-1,n-2,...,1. for (i= JointNum -2;i>=0;i--) { for (j=0;j<6;j++) { V[j] = -1.0*Blist[j*JointNum+i+1]; } VecTose3(V, se3mat); Matrix4MultValue(se3mat, thetalist[i + 1], se3mat); MatrixExp6(se3mat, T1); Matrix4Mult(T, T1,T2); Matrix4Equal(T2, T); Adjoint(T, AdT); for (j=0;j<6; j++) { Jb[j*JointNum + i] = 0; for (k=0;k<6;k++) { Jb[j*JointNum + i] = Jb[j*JointNum + i] + AdT[j][k] * Blist[k*JointNum + i]; } } } return ; } /** *@brief Description:Computes the space Jacobian Js(theta) in R6 x n given a list of joint screws Si * expressed in the fixed space frame and a list of joint angles. *@param[in] JointNum joints number. *@param[in] Slist The joint screw axes expressed in the fixed space frame when the manipulator is * at the home position, in the format of a matrix with the screw axes as the column. *@param[in] thetalist A list of joint coordinates. *@param[out] Js Space Jacobian matrix. *@return No return value. *@note: when Slist and Js are matrices ,make sure that columns number of Slist or Js is equal to JointNum, * rows number of Slist or Js is 6 .The function call should be written as * JacobianSpace(JointNum,(double *)Slist,thetalist,(double *)Js). *@warning: */ void JacobianSpace(int JointNum, double *Slist, double *thetalist, double *Js) { int i; int j; int k; double T1[4][4]; double T2[4][4]; double se3mat[4][4]; double V[6]; double AdT[6][6]; double T[4][4] = { 1,0,0,0, 0,1,0,0, 0,0,1,0, 0,0,0,1 }; //Fist column of Js. for (i = 0; i < 6; i++) { Js[i*JointNum + 0] = Slist[i*JointNum + 0]; } //Jsi for i=2,3,...,n. for (i = 1; i = 0.0 ? fabs(a) : -fabs(a)) #define MAX(a,b) (a>b?a:b) #define MIN(a,b) (a absb) return absa*sqrt(1.0 + (absb / absa)*(absb / absa)); else return (absb == 0.0 ? 0.0 : absb*sqrt(1.0 + (absa / absb)*(absa / absb))); } void reorder(double *u,int m,int n,double *w,double *v) { /*Given the output of decompose, this routine sorts the singular values, and corresponding columns of u and v, by decreasing magnitude.Also, signs of corresponding columns are flipped so as to maximize the number of positive elements.*/ int i, j, k, s, inc = 1; double sw; double *su = (double *)malloc(m * sizeof(double)); if (su==NULL) { return; } double *sv = (double *)malloc(n * sizeof(double)); if (sv==NULL) { free(su); return; } do { inc *= 3; inc++; } while (inc <= n);// Sort.The method is Shell’s sort.(The work is negligible as compared to that already done in decompose.) do { inc /= 3; for (i = inc; i < n; i++) { sw = w[i]; for (k = 0; k < m; k++) su[k] = u[k*n + i]; for (k = 0; k < n; k++) sv[k] = v[k*n + i]; j = i; while (w[j - inc] < sw) { w[j] = w[j - inc]; for (k = 0; k < m; k++) u[k*n + j] = u[k*n + j - inc]; for (k = 0; k < n; k++) v[k*n + j] = v[k*n + j - inc]; j -= inc; if (j < inc) break; } w[j] = sw; for (k = 0; k < m; k++) u[k*n + j] = su[k]; for (k = 0; k < n; k++) v[k*n + j] = sv[k]; } } while (inc > 1); for (k = 0; k < n; k++) { //Flip signs. s = 0; for (i = 0; i < m; i++) if (u[i*n + k] < 0.0) s++; for (j = 0; j < n; j++) if (v[j*n + k] < 0.0) s++; if (s > (m + n) / 2) { for (i = 0; i < m; i++) u[i*n + k] = -u[i*n + k]; for (j = 0; j < n; j++) v[j*n + k] = -v[j*n + k]; } } free(su); free(sv); return; } /** *@brief Given the matrix a,this routine computes its singular value decomposition. *@param[in/out] a input matrix a or output matrix u. *@param[in] m number of rows of matrix a. *@param[in] n number of columns of matrix a. *@param[in] tol any singular values less than a tolerance are treated as zero. *@param[out] w output vector w. *@param[out] v output matrix v. *@return No return value. *@note: input a must be a m rows and n columns matrix,w is n-vector,v is a n rows and n columns matrix. *@warning: */ int svdcmp(double *a, int m, int n, double tol, double *w, double *v) { int flag, i, its, j, jj, k, l, nm; double anorm, c, f, g, h, s, scale, x, y, z; double *rv1 = (double *)malloc(n * sizeof(double)); if (rv1==NULL) { return 1; } g = scale = anorm = 0.0; for (i=0;i=0;i--)//Accumulation of right-hand transformations. { if (i=0;i--)//Accumulation of left-hand transformations. { l = i + 1; g = w[i]; for (j = l;j=0;k--) { /* Diagonalization of the bidiagonal form: Loop over singular values, and over allowed iterations. */ for (its=0;its<30;its++) { flag = 1; for (l = k;l>=0;l--)//Test for splitting. { nm = l - 1; if (l==0 || fabs(rv1[l])<= tol*anorm) { flag = 0; break; } if (fabs(w[nm]) <=tol*anorm)break; } if (flag)//Cancellation of rv1[l], if l > 0. { c = 0.0; s = 1.0; for (i=l;i eomg || VecNorm2(3, &Vb[3]) > ev; i = 0; #if(DEBUGMODE) ///////////////////Debug/////////// printf("iteration:%4d thetalist: ", i); int k; for (k = 0; k < JointNum; k++) { printf("%4.6lf\t", thetalist[k]); } printf("\n"); //////////////////////////////////// #endif while (ErrFlag && i eomg || VecNorm2(3, &Vb[3]) > ev; #if (DEBUGMODE) ///////////////////////DEBUG/////////// printf("iteration:%4d thetalist: ", i); for (k = 0; k < JointNum; k++) { printf("%4.6lf\t", thetalist[k]); } printf("\n"); ////////////////////////////////////// #endif } free(Jb); free(pJb); free(dtheta); return ErrFlag; } /** *@brief Description:use an iterative Newton-Raphson root-finding method. *@param[in] JointNum Number of joints. *@param[in] Slist The joint screw axes in the space frame when the manipulator * is at the home position, in the format of a matrix with the * screw axes as the columns. *@param[in] M The home configuration of the end-effector. *@param[in] T The desired end-effector configuration Tsd. *@param[in] thetalist0 An initial guess of joint angles that are close to satisfying Tsd. *@param[in] eomg A small positive tolerance on the end-effector orientation error. * The returned joint angles must give an end-effector orientation error less than eomg. *@param[in] ev A small positive tolerance on the end-effector linear position error. The returned * joint angles must give an end-effector position error less than ev. *@param[in] maxiter The maximum number of iterations before the algorithm is terminated. *@param[out] thetalist Joint angles that achieve T within the specified tolerances. *@return 0:success,Nonzero:failure *@retval 0 *@note : *@warning: */ int IKinSpaceNR(int JointNum, double *Slist, double M[4][4], double T[4][4], double *thetalist0, double eomg, double ev, int maxiter,double *thetalist) { int i, j; double Tsb[4][4]; double iTsb[4][4]; double Tbd[4][4]; double AdT[6][6]; double se3Mat[4][4]; double Vb[6]; double Vs[6]; int ErrFlag; double *Js = (double *)malloc(JointNum * 6 * sizeof(double)); if (Js == NULL) { return 2; } double *pJs = (double *)malloc(JointNum * 6 * sizeof(double)); if (pJs == NULL) { free(Js); return 2; } double *dtheta = (double *)malloc(JointNum * sizeof(double)); if (dtheta == NULL) { free(Js); free(pJs); return 2; } MatrixCopy(thetalist0, JointNum, 1, thetalist); FKinSpace(M, JointNum, Slist, thetalist, Tsb); TransInv(Tsb, iTsb); Matrix4Mult(iTsb, T, Tbd); MatrixLog6(Tbd, se3Mat); se3ToVec(se3Mat, Vb); Adjoint(Tsb, AdT); MatrixMult((double *)AdT, 6, 6, Vb, 1, Vs); ErrFlag = VecNorm2(3, &Vs[0]) > eomg || VecNorm2(3, &Vs[3]) > ev; i = 0; #if(DEBUGMODE) ///////////////////Debug/////////// printf("iteration:%4d thetalist: ", i); int k; for (k = 0; k < JointNum; k++) { printf("%4.4lf, ", thetalist[k]); } printf("\n"); //////////////////////////////////// #endif while (ErrFlag && i < maxiter) { JacobianSpace(JointNum, Slist, thetalist, Js); MatrixPinv(Js, 6, JointNum, 2.2E-15, pJs); MatrixMult(pJs, JointNum, 6, Vs, 1, dtheta); for (j = 0; j < JointNum; j++) { thetalist[j] = thetalist[j] + dtheta[j]; } i++; FKinSpace(M, JointNum, Slist, thetalist, Tsb); TransInv(Tsb, iTsb); Matrix4Mult(iTsb, T, Tbd); MatrixLog6(Tbd, se3Mat); se3ToVec(se3Mat, Vb); Adjoint(Tsb, AdT); MatrixMult((double *)AdT, 6, 6, Vb, 1, Vs); ErrFlag = VecNorm2(3, &Vs[0]) > eomg || VecNorm2(3, &Vs[3]) > ev; #if (DEBUGMODE) ///////////////////////DEBUG/////////// printf("iteration:%4d thetalist: ", i); for (k = 0; k < JointNum; k++) { printf("%4.4lf, ", thetalist[k]); } printf("\n"); ////////////////////////////////////// #endif } free(Js); free(pJs); free(dtheta); return ErrFlag; } /** * @brief Description: Algorithm for Computing the ZYX Euler Angles according to rotation matrix. * @param[in] R Rotation matrix. * @param[out] alpha Angles for rotation around Z axis. * @param[out] beta Angles for rotation around Y axis. * @param[out] gamma Angles for rotation around X axis. * @return No return value. * @note: *@warning: */ void RotToZYXEulerAngle(double R[3][3], double *alpha, double *beta, double *gamma) { if (fabs(1.0 + R[2][0])= ZERO_VALUE) { omg[0] = 1.0 / sqrt(2 * (1.0 + R[2][2]))*R[0][2]; omg[1] = 1.0 / sqrt(2 * (1.0 + R[2][2]))*R[1][2]; omg[2] = 1.0 / sqrt(2 * (1.0 + R[2][2]))*(1.0 + R[2][2]); } else if ((1.0 + R[1][1] >= ZERO_VALUE)) { omg[0] = 1.0 / sqrt(2 * (1.0 + R[1][1]))*R[0][1]; omg[1] = 1.0 / sqrt(2 * (1.0 + R[1][1]))*(1.0 + R[1][1]); omg[2] = 1.0 / sqrt(2 * (1.0 + R[1][1]))*R[2][1]; } else { omg[0] = 1.0 / sqrt(2 * (1.0 + R[0][0]))*(1.0 + R[0][0]); omg[1] = 1.0 / sqrt(2 * (1.0 + R[0][0]))*R[1][0]; omg[2] = 1.0 / sqrt(2 * (1.0 + R[0][0]))*R[2][0]; } omghat[0] = omg[0]; omghat[1] = omg[1]; omghat[2] = omg[2]; *theta=PI; } else { *theta = acos(acosinput); tmp = 2.0*sin(*theta); omghat[0] = (R[2][1] - R[1][2]) / tmp; omghat[1] = (R[0][2] - R[2][0]) / tmp; omghat[2] = (R[1][0] - R[0][1]) / tmp; } return; } /** * @brief Description: Computes the unit quaternion corresponding to the Euler axis and rotation angle. * @param[in] omg Unit vector of Euler axis. * @param[in] theta Rotation angle. * @param[in] q The unit quaternion * @return No return value. * @note: *@warning: */ void AxisAngToQuaternion(double omg[3],double theta, double q[4]) { q[0] = cos(theta / 2.0); q[1] = omg[0] * sin(theta / 2.0); q[2] = omg[1] * sin(theta / 2.0); q[3] = omg[2] * sin(theta / 2.0); return; } /** * @brief Description:Computes the unit quaternion corresponding to a rotation matrix. * @param[in] q Unit quaternion. * @param[out] R Rotation matrix. * @return No return value. * @note: * @warning: */ void QuaternionToRot(double q[4], double R[3][3]) { R[0][0] = q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]; R[0][1] = 2.0*(q[1] * q[2] - q[0] * q[3]); R[0][2] = 2.0*(q[0] * q[2] + q[1] * q[3]); R[1][0] = 2.0*(q[0] * q[3] + q[1] * q[2]); R[1][1] = q[0] * q[0] - q[1] * q[1] + q[2] * q[2] - q[3] * q[3]; R[1][2] = 2.0*(q[2] * q[3] - q[0] * q[1]); R[2][0] = 2.0*(q[1] * q[3] - q[0] * q[2]); R[2][1] = 2.0*(q[0] * q[1] + q[2] * q[3]); R[2][2] = q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]; return; } /** * @brief Description: Computes the unit quaternion corresponding to the rotation matrix. * @param[in] R The rotation matrix. * @param[out] q The unit quaternion. * @return No return value. * @note: * @warning: */ void RotToQuaternion(double R[3][3], double q[4]) { double omghat[3]; double theta; RotToAxisAng(R, omghat, &theta); AxisAngToQuaternion(omghat, theta, q); return; } /** * @brief 单位四元数转换为旋转矩阵。 * @param[in] q 单位四元数[ox,oy,oz,ow]. * @param[out] R 旋转矩阵. * @return 无返回值. * @note: * @warning: (1)此函数不对输入参数做检查,需保证输入为单位四元数。 (2)四元数顺序为[ox,oy,oz,w]。 */ void q2rot(double q[4], double R[3][3]) { double q1[4] = { 0 }; q1[0] = q[3]; q1[1] = q[0]; q1[2] = q[1]; q1[3] = q[2]; QuaternionToRot(q1, R); return; } /** * @brief 旋转矩阵转单位四元数。 * @param[in] R 旋转矩阵 * @param[out] q 单位四元数.[ox,oy,oz,ow]. * @return 无返回值. * @note: * @warning: (1)此函数不对输入参数做检查,需保证输入为旋转矩阵。 (2)四元数顺序为[ox,oy,oz,w]。 */ void rot2q(double R[3][3], double q[4]) { double q1[4] = { 0 }; RotToQuaternion(R, q1); q[0] = q1[1]; q[1] = q1[2]; q[2] = q1[3]; q[3] = q1[0]; return; } /** * @brief Description: Computes the parameters of orientation interpolation between two orientations. * @param[in] Rs Start orientation. * @param[in] Re End orientation. * @param[in] Param structure of orientation interpolation parameters.. * @return No return value. * @note: * @warning: */ void InitialOrientInpParam(double Rs[3][3],double Re[3][3], OrientInpParam *Param) { double InvR[3][3]; MatrixCopy((double *)Rs, 3, 3, (double *)Param->Rs); MatrixCopy((double *)Re, 3, 3, (double *)Param->Re); RotInv(Rs, InvR); MatrixMult((double *)InvR, 3, 3, (double *)Re, 3, (double *)Param->R); RotToAxisAng(Param->R, Param->omg, &Param->theta); MatrixCopy((double *)Param->R, 3, 3, (double *)Param->Ri); Param->thetai = 0.0; Param->InpFlag = 1; return; } /** * @brief Description: Computes orientations in each interpolation cycle. * @param[in] Param Interpolation parameter structure. * @param[out] dtheta angle need to rotate from previous orientation to next orientation in next time step. * @return Ri1 orientations in next interpolation cycle. * @retval 0 * @note: * @warning: */ void QuaternionOrientInp(OrientInpParam *Param, double dtheta, double Ri1[3][3]) { double q[4]; double R[3][3]; Param->InpFlag = 2; Param->thetai = Param->thetai + dtheta; if (Param->thetai >= Param->theta) { Param->thetai = Param->theta; Param->InpFlag = 3; } AxisAngToQuaternion(Param->omg, Param->thetai, q); QuaternionToRot(q, R); MatrixMult((double *)Param->Rs, 3, 3, (double *)R, 3, (double *)Ri1); MatrixCopy((double *)Ri1, 3, 3, (double *)Param->Ri); return; } /** * @brief Description:Computes the parameters of line path for interpolation. * @param[in] p1 Coordinates of start point. * @param[in] p2 Coordinates of end point. * @param[out] p Line path parameters structure. * @return No return value. * @note: * @warning: */ void InitialLinePathParam(double p1[3],double p2[3], LineInpParam *p) { int i; for (i=0;i<3;i++) { p->p1[i] = p1[i]; p->p2[i] = p2[i]; p->pi[i] = p1[i]; } p->L = sqrt((p2[0] - p1[0])*(p2[0] - p1[0]) + (p2[1] - p1[1])*(p2[1] - p1[1]) + (p2[2] - p1[2])*(p2[2] - p1[2])); if (p->Lt[0] = 0.0; p->t[1] = 0.0; p->t[2] = 0.0; } else { p->t[0] = (p2[0] - p1[0]) / p->L; p->t[1] = (p2[1] - p1[1]) / p->L; p->t[2] = (p2[2] - p1[2]) / p->L; } p->InpFlag = 1; p->Li = 0; return; } /** * @brief Description:Computes the line path interpolation coordinates in each interpolation cycle. * @param[in] p Line path parameters structure. * @param[in] dL step length in next interpolation cycle. * @param[in] pi1 coordinates in next interpolation cycle. * @return No return value. * @note: * @warning: */ void LinePathInp(LineInpParam *p, double dL, double pi1[3]) { p->InpFlag = 2; if (p->Li + dL>=p->L) { pi1[0] = p->p2[0]; pi1[1] = p->p2[1]; pi1[2] = p->p2[2]; p->Li = p->L; p->InpFlag = 3; } else if ( p->L- p->Li < 2.0*dL) { //avoid distance of final step is too small. dL = 0.5*dL; pi1[0] = p->pi[0] + p->t[0] * dL; pi1[1] = p->pi[1] + p->t[1] * dL; pi1[2] = p->pi[2] + p->t[2] * dL; p->Li = p->Li+dL; } else { pi1[0] = p->pi[0] + p->t[0] * dL; pi1[1] = p->pi[1] + p->t[1] * dL; pi1[2] = p->pi[2] + p->t[2] * dL; p->Li = p->Li + dL; } p->pi[0] = pi1[0]; p->pi[1] = pi1[1]; p->pi[2] = pi1[2]; return; } /** * @brief Description: Computes the parameters of both line path and orientation for interpolation. * @param[in] p1 Start coordinates,including x,y,z coordinates and orientation angles roll-pitch-yaw angles. * @param[in] p2 End coordinates,including x,y,z coordinates and orientation angles roll-pitch-yaw angles. * @param[out] LPO Parameters of both line path and orientation for interpolation. * @return No return value. * @note: * @warning: */ void InitialLinePOInpParam( double p1[6], double p2[6], LinePOParam *LPO) { double Rs[3][3]; double Re[3][3]; RPYToRot(p1[3], p1[4], p1[5], Rs); RPYToRot(p2[3], p2[4], p2[5], Re); InitialLinePathParam( p1, p2, &(LPO->Line)); InitialOrientInpParam(Rs, Re, &(LPO->Orient)); RpToTrans(Rs, p1, LPO->Ts); RpToTrans(Rs, p1, LPO->Ti); RpToTrans(Re, p2, LPO->Te); LPO->InpFlag = 1; return; } /** * @brief Description:Computes the line path interpolation coordinates and orientation in each interpolation cycle. * @param[out] LPO Line path and orientation parameters structure. * @param[in] dL Line path interpolation step length. * @param[out] dtheta angle interpolation step length for Orientation interpolation. * @return No return value. * @note: * @warning: */ void LinePOInp(LinePOParam *LPO,double dL,double dtheta,double Ti[4][4]) { double pi[3]; double Ri[3][3]; LPO->InpFlag = 2; LinePathInp(&LPO->Line, dL, pi); QuaternionOrientInp(&LPO->Orient, dtheta, Ri); if (LPO->Line.InpFlag==3 && LPO->Orient.InpFlag==3) { LPO->InpFlag = 3; } RpToTrans(Ri, pi, Ti); MatrixCopy((double *)Ti, 4, 4, (double *)LPO->Ti); return; }