$search
00001 // This controller implements a cartesian impedance (stiffness and damping) 00002 // on top of joint impedance control. 00003 // 00004 // The allowed inputs are: 00005 // 00006 // q_desired, K_cart, D_cart, ft_cart 00007 // 00008 // The cartesian parameters are expressed in the reference frame of the base 00009 // with the reference point flanche. 00010 00011 #include "CartesianImpedance.hh" 00012 #include <kdl/frames.hpp> 00013 #include <kdl/jacobian.hpp> 00014 #include <kdl/jntarray.hpp> 00015 #include <kdl/chain.hpp> 00016 #include <kdl/chainjnttojacsolver.hpp> 00017 00018 00019 #include <kdl/utilities/svd_eigen_HH.hpp> 00020 #include <Eigen/Core> 00021 00022 using namespace KDL; 00023 using namespace Eigen; 00024 00025 00026 // note: K and D are 6-vectors in the FRI structs. 00027 // (those guys 'simplified' the interface) 00028 // Is that bad for us? Well ... 00029 // ... No. We just don't use it :) 00030 00031 00032 CartesianImpedanceControl::CartesianImpedanceControl() 00033 : q_kdl_(7), jnt2jac_(0), J_kdl_(7), 00034 U(6,7), V(6,6), S(7), Sp(7), tmp(7) 00035 { 00036 chain_.addSegment(Segment(Joint(Joint::None), 00037 Frame::DH_Craig1989(0.0, 0.0, 0.31, 0.0))); 00038 chain_.addSegment(Segment(Joint(Joint::RotZ), 00039 Frame::DH_Craig1989(0.0, 1.5707963, 0.0, 0.0))); 00040 chain_.addSegment(Segment(Joint(Joint::RotZ), 00041 Frame::DH_Craig1989(0.0, -1.5707963, 0.4, 0.0))); 00042 chain_.addSegment(Segment(Joint(Joint::RotZ), 00043 Frame::DH_Craig1989(0.0, -1.5707963, 0.0, 0.0))); 00044 chain_.addSegment(Segment(Joint(Joint::RotZ), 00045 Frame::DH_Craig1989(0.0, 1.5707963, 0.39, 0.0))); 00046 chain_.addSegment(Segment(Joint(Joint::RotZ), 00047 Frame::DH_Craig1989(0.0, 1.5707963, 0.0, 0.0))); 00048 chain_.addSegment(Segment(Joint(Joint::RotZ), 00049 Frame::DH_Craig1989(0.0, -1.5707963, 0.0, 0.0))); 00050 chain_.addSegment(Segment(Joint(Joint::RotZ), 00051 Frame::Identity())); 00052 00053 jnt2jac_ = new ChainJntToJacSolver(chain_); 00054 } 00055 00056 00057 CartesianImpedanceControl::~CartesianImpedanceControl() 00058 { 00059 delete jnt2jac_; 00060 } 00061 00062 00065 tFriCmdData CartesianImpedanceControl::computeRobotCommand(const tFriMsrData& fri_msr, 00066 const tFriCmdData& fri_cmd, const CartesianImpedance& imp, const float* cmdpos) 00067 { 00068 for(int i=0; i < 7; i++) 00069 { 00070 q_last_[i] = fri_msr.data.msrJntPos[i]; 00071 00072 q_kdl_(i) = fri_msr.data.msrJntPos[i]; 00073 } 00074 00075 // define matrix expressions for most of the matrices we use. 00076 PlainObjectBase<Matrix<float, 7, 1> > q_des = Matrix<float, 7, 1>::Map(&(fri_cmd.cmd.jntPos[0])); 00077 PlainObjectBase<Matrix<float, 7, 1> > q_cmd = Matrix<float, 7, 1>::Map(&(cmdpos[0])); 00078 PlainObjectBase<Matrix<float, 7, 1> > q = Matrix<float, 7, 1>::Map(&(fri_msr.data.msrJntPos[0])); 00079 PlainObjectBase<Matrix<float, 7, 7> > M = Matrix<float, 7, 7, RowMajor>::Map(&(fri_msr.data.massMatrix[0])); 00080 00081 PlainObjectBase<Matrix<float, 6, 6> > D = Matrix<float, 6, 6, RowMajor>::Map(&(imp.D[0])); 00082 PlainObjectBase<Matrix<float, 6, 6> > K = Matrix<float, 6, 6, RowMajor>::Map(&(imp.K[0])); 00083 PlainObjectBase<Matrix<float, 6, 1> > ft = Matrix<float, 6, 1>::Map(&(imp.ft[0])); 00084 00085 // compute Jacobian 00086 jnt2jac_->JntToJac(q_kdl_, J_kdl_); 00087 // Eigen requires us to explicitly cast this data type, sorry... 00088 PlainObjectBase<Eigen::Matrix<float,6,7> > J = J_kdl_.data.cast<float>(); 00089 00090 // since no reliable information on the 00091 // 'normalization' of the damping was to be found, 00092 // we stick with the joint damping controllers only. 00093 Matrix<float, 7, 1> damping = (J.transpose()*D*J).diagonal(); 00094 00095 // Note: we are ignoring the term (dJ^T/dq^T)*K*deltax. 00096 // Assuming that J does not change much in one cartesian cycle, 00097 // we spare ourselves the hassle of deriving J once more. 00098 Matrix<float, 7, 1> stiffness = (J.transpose()*K*J).diagonal(); 00099 00100 // this value can use the full matrix K, which the joint impedance controllers can't 00101 Matrix<float, 7, 1> tau_add = J.transpose() * (K*J*(q_des - q) + ft) - stiffness.asDiagonal()*(q_cmd - q); 00102 00103 00104 // null space stiffness, commented, requires testing 00105 //pinv(J_kdl_.data, Jinv); 00106 00107 //Matrix<float, 7, 1> K_null; 00108 //float s = imp.K_null; 00109 //K_null << s, s, s, s, s, s, s; 00110 00111 //TODO: compute correct mass matrix 00112 //MatrixXf tau_null = Jinv*J*K_null.asDiagonal()*(q_des - q); 00113 00114 //tau_add += tau_null; 00115 00116 00117 tFriCmdData fri_cmd_cart=fri_cmd; 00118 for(int i=0; i < 7; i++) 00119 { 00120 fri_cmd_cart.cmd.jntPos[i] = cmdpos[i]; 00121 fri_cmd_cart.cmd.addJntTrq[i] = fri_cmd.cmd.addJntTrq[i] + tau_add(i); 00122 fri_cmd_cart.cmd.jntStiffness[i] = stiffness(i); 00123 fri_cmd_cart.cmd.jntDamping[i] = damping(i); 00124 } 00125 00126 return fri_cmd_cart; 00127 } 00128 00129 00130 template <typename T1, typename T2> 00131 void CartesianImpedanceControl::pinv(Eigen::DenseBase<T1>& J, Eigen::DenseBase<T2>& Jinv, double eps) 00132 { 00133 svd_eigen_HH(J, U, S, V, tmp); 00134 00135 for(int i=0; i < 7; ++i) 00136 Sp(i) = (fabs(S(i)) > eps) ? 1.0 / S(i) : 0.0; 00137 00138 Jinv = (V * Sp.asDiagonal() * U.transpose()).cast<typename T2::Scalar>(); 00139 } 00140