Blender V2.61 - r43446
|
00001 00004 /* 00005 * ConstraintSet.cpp 00006 * 00007 * Created on: Jan 5, 2009 00008 * Author: rubensmits 00009 */ 00010 00011 #include "ConstraintSet.hpp" 00012 #include "kdl/utilities/svd_eigen_HH.hpp" 00013 00014 namespace iTaSC { 00015 00016 ConstraintSet::ConstraintSet(unsigned int _nc,double accuracy,unsigned int maximum_iterations): 00017 m_nc(_nc), 00018 m_Cf(e_zero_matrix(m_nc,6)), 00019 m_Wy(e_scalar_vector(m_nc,1.0)), 00020 m_y(m_nc),m_ydot(e_zero_vector(m_nc)),m_chi(e_zero_vector(6)), 00021 m_S(6),m_temp(6),m_tdelta(6), 00022 m_Jf(e_identity_matrix(6,6)), 00023 m_U(e_identity_matrix(6,6)),m_V(e_identity_matrix(6,6)),m_B(e_zero_matrix(6,6)), 00024 m_Jf_inv(e_zero_matrix(6,6)), 00025 m_internalPose(F_identity), m_externalPose(F_identity), 00026 m_constraintCallback(NULL), m_constraintParam(NULL), 00027 m_toggle(false),m_substep(false), 00028 m_threshold(accuracy),m_maxIter(maximum_iterations) 00029 { 00030 m_maxDeltaChi = e_scalar(0.52); 00031 } 00032 00033 ConstraintSet::ConstraintSet(): 00034 m_nc(0), 00035 m_internalPose(F_identity), m_externalPose(F_identity), 00036 m_constraintCallback(NULL), m_constraintParam(NULL), 00037 m_toggle(false),m_substep(false), 00038 m_threshold(0.0),m_maxIter(0) 00039 { 00040 m_maxDeltaChi = e_scalar(0.52); 00041 } 00042 00043 void ConstraintSet::reset(unsigned int _nc,double accuracy,unsigned int maximum_iterations) 00044 { 00045 m_nc = _nc; 00046 m_Jf = e_identity_matrix(6,6); 00047 m_Cf = e_zero_matrix(m_nc,6); 00048 m_U = e_identity_matrix(6,6); 00049 m_V = e_identity_matrix(6,6); 00050 m_B = e_zero_matrix(6,6); 00051 m_Jf_inv = e_zero_matrix(6,6), 00052 m_Wy = e_scalar_vector(m_nc,1.0), 00053 m_chi = e_zero_vector(6); 00054 m_chidot = e_zero_vector(6); 00055 m_y = e_zero_vector(m_nc); 00056 m_ydot = e_zero_vector(m_nc); 00057 m_S = e_zero_vector(6); 00058 m_temp = e_zero_vector(6); 00059 m_tdelta = e_zero_vector(6); 00060 m_threshold = accuracy; 00061 m_maxIter = maximum_iterations; 00062 } 00063 00064 ConstraintSet::~ConstraintSet() { 00065 00066 } 00067 00068 void ConstraintSet::modelUpdate(Frame& _external_pose,const Timestamp& timestamp) 00069 { 00070 m_chi+=m_chidot*timestamp.realTimestep; 00071 m_externalPose = _external_pose; 00072 00073 //update the internal pose and Jf 00074 updateJacobian(); 00075 //check if loop is already closed, if not update the pose and Jf 00076 unsigned int iter=0; 00077 while(iter<5&&!closeLoop()) 00078 iter++; 00079 } 00080 00081 double ConstraintSet::getMaxTimestep(double& timestep) 00082 { 00083 e_scalar maxChidot = m_chidot.array().abs().maxCoeff(); 00084 if (timestep*maxChidot > m_maxDeltaChi) { 00085 timestep = m_maxDeltaChi/maxChidot; 00086 } 00087 return timestep; 00088 } 00089 00090 bool ConstraintSet::initialise(Frame& init_pose){ 00091 m_externalPose=init_pose; 00092 // get current Jf 00093 updateJacobian(); 00094 00095 unsigned int iter=0; 00096 while(iter<m_maxIter&&!closeLoop()){ 00097 iter++; 00098 } 00099 if (iter<m_maxIter) 00100 return true; 00101 else 00102 return false; 00103 } 00104 00105 bool ConstraintSet::setControlParameter(int id, ConstraintAction action, double data, double timestep) 00106 { 00107 ConstraintValues values; 00108 ConstraintSingleValue value; 00109 values.values = &value; 00110 values.number = 0; 00111 values.action = action; 00112 values.id = id; 00113 value.action = action; 00114 value.id = id; 00115 switch (action) { 00116 case ACT_NONE: 00117 return true; 00118 case ACT_VALUE: 00119 value.yd = data; 00120 values.number = 1; 00121 break; 00122 case ACT_VELOCITY: 00123 value.yddot = data; 00124 values.number = 1; 00125 break; 00126 case ACT_TOLERANCE: 00127 values.tolerance = data; 00128 break; 00129 case ACT_FEEDBACK: 00130 values.feedback = data; 00131 break; 00132 case ACT_ALPHA: 00133 values.alpha = data; 00134 break; 00135 default: 00136 assert(action==ACT_NONE); 00137 break; 00138 } 00139 return setControlParameters(&values, 1, timestep); 00140 } 00141 00142 bool ConstraintSet::closeLoop(){ 00143 //Invert Jf 00144 //TODO: svd_boost_Macie has problems if Jf contains zero-rows 00145 //toggle=!toggle; 00146 //svd_boost_Macie(Jf,U,S,V,B,temp,1e-3*threshold,toggle); 00147 int ret = KDL::svd_eigen_HH(m_Jf,m_U,m_S,m_V,m_temp); 00148 if(ret<0) 00149 return false; 00150 00151 // the reference point and frame of the jacobian is the base frame 00152 // m_externalPose-m_internalPose is the twist to extend the end effector 00153 // to get the required pose => change the reference point to the base frame 00154 Twist twist_delta(diff(m_internalPose,m_externalPose)); 00155 twist_delta=twist_delta.RefPoint(-m_internalPose.p); 00156 for(unsigned int i=0;i<6;i++) 00157 m_tdelta(i)=twist_delta(i); 00158 //TODO: use damping in constraintset inversion? 00159 for(unsigned int i=0;i<6;i++) 00160 if(m_S(i)<m_threshold){ 00161 m_B.row(i).setConstant(0.0); 00162 }else 00163 m_B.row(i) = m_U.col(i)/m_S(i); 00164 00165 m_Jf_inv.noalias()=m_V*m_B; 00166 00167 m_chi.noalias()+=m_Jf_inv*m_tdelta; 00168 updateJacobian(); 00169 // m_externalPose-m_internalPose in end effector frame 00170 // this is just to compare the pose, a different formula would work too 00171 return Equal(m_internalPose.Inverse()*m_externalPose,F_identity,m_threshold); 00172 00173 } 00174 }