Blender V2.61 - r43446

Distance.cpp

Go to the documentation of this file.
00001 
00004 /*
00005  * Distance.cpp
00006  *
00007  *  Created on: Jan 30, 2009
00008  *      Author: rsmits
00009  */
00010 
00011 #include "Distance.hpp"
00012 #include "kdl/kinfam_io.hpp"
00013 #include <math.h>
00014 #include <string.h>
00015 
00016 namespace iTaSC
00017 {
00018 // a distance constraint is characterized by 5 values: alpha, tolerance, K, yd, yddot
00019 static const unsigned int distanceCacheSize = sizeof(double)*5 + sizeof(e_scalar)*6;
00020 
00021 Distance::Distance(double armlength, double accuracy, unsigned int maximum_iterations):
00022     ConstraintSet(1,accuracy,maximum_iterations),
00023     m_chiKdl(6),m_jac(6),m_cache(NULL),
00024     m_distCCh(-1),m_distCTs(0)
00025 {
00026     m_chain.addSegment(Segment(Joint(Joint::RotZ)));
00027     m_chain.addSegment(Segment(Joint(Joint::RotX)));
00028     m_chain.addSegment(Segment(Joint(Joint::TransY)));
00029     m_chain.addSegment(Segment(Joint(Joint::RotZ)));
00030     m_chain.addSegment(Segment(Joint(Joint::RotY)));
00031     m_chain.addSegment(Segment(Joint(Joint::RotX)));
00032 
00033     m_fksolver = new KDL::ChainFkSolverPos_recursive(m_chain);
00034     m_jacsolver = new KDL::ChainJntToJacSolver(m_chain);
00035     m_Cf(0,2)=1.0;
00036     m_alpha = 1.0;
00037     m_tolerance = 0.05;
00038     m_maxerror = armlength/2.0;
00039     m_K = 20.0;
00040     m_Wy(0) = m_alpha/*/(m_tolerance*m_K)*/;
00041     m_yddot = m_nextyddot = 0.0;
00042     m_yd = m_nextyd = KDL::epsilon;
00043     memset(&m_data, 0, sizeof(m_data));
00044     // initialize the data with normally fixed values
00045     m_data.id = ID_DISTANCE;
00046     m_values.id = ID_DISTANCE;
00047     m_values.number = 1;
00048     m_values.alpha = m_alpha;
00049     m_values.feedback = m_K;
00050     m_values.tolerance = m_tolerance;
00051     m_values.values = &m_data;
00052 }
00053 
00054 Distance::~Distance()
00055 {
00056     delete m_fksolver;
00057     delete m_jacsolver;
00058 }
00059 
00060 bool Distance::computeChi(Frame& pose)
00061 {
00062     double dist, alpha, beta, gamma;
00063     dist = pose.p.Norm();
00064     Rotation basis;
00065     if (dist < KDL::epsilon) {
00066         // distance is almost 0, no need for initial rotation
00067         m_chi(0) = 0.0;
00068         m_chi(1) = 0.0;
00069     } else {
00070         // find the XZ angles that bring the Y axis to point to init_pose.p
00071         Vector axis(pose.p/dist);
00072         beta = 0.0;
00073         if (fabs(axis(2)) > 1-KDL::epsilon) {
00074             // direction is aligned on Z axis, just rotation on X
00075             alpha = 0.0;
00076             gamma = KDL::sign(axis(2))*KDL::PI/2;
00077         } else {
00078             alpha = -KDL::atan2(axis(0), axis(1));
00079             gamma = KDL::atan2(axis(2), KDL::sqrt(KDL::sqr(axis(0))+KDL::sqr(axis(1))));
00080         }
00081         // rotation after first 2 joints
00082         basis = Rotation::EulerZYX(alpha, beta, gamma);
00083         m_chi(0) = alpha;
00084         m_chi(1) = gamma;
00085     }
00086     m_chi(2) = dist;
00087     basis = basis.Inverse()*pose.M;
00088     basis.GetEulerZYX(alpha, beta, gamma);
00089     // alpha = rotation on Z
00090     // beta = rotation on Y
00091     // gamma = rotation on X in that order
00092     // it corresponds to the joint order, so just assign
00093     m_chi(3) = alpha;
00094     m_chi(4) = beta;
00095     m_chi(5) = gamma;
00096     return true;
00097 }
00098 
00099 bool Distance::initialise(Frame& init_pose)
00100 {
00101     // we will initialize m_chi to values that match the pose
00102     m_externalPose=init_pose;
00103     computeChi(m_externalPose);
00104     // get current Jf and update internal pose
00105     updateJacobian();
00106     return true;
00107 }
00108 
00109 bool Distance::closeLoop()
00110 {
00111     if (!Equal(m_internalPose.Inverse()*m_externalPose,F_identity,m_threshold)){
00112         computeChi(m_externalPose);
00113         updateJacobian();
00114     }
00115     return true;
00116 }
00117 
00118 void Distance::initCache(Cache *_cache)
00119 {
00120     m_cache = _cache;
00121     m_distCCh = -1;
00122     if (m_cache) {
00123         // create one channel for the coordinates
00124         m_distCCh = m_cache->addChannel(this, "Xf", distanceCacheSize);
00125         // save initial constraint in cache position 0
00126         pushDist(0);
00127     }
00128 }
00129 
00130 void Distance::pushDist(CacheTS timestamp)
00131 {
00132     if (m_distCCh >= 0) {
00133         double *item = (double*)m_cache->addCacheItem(this, m_distCCh, timestamp, NULL, distanceCacheSize);
00134         if (item) {
00135             *item++ = m_K;
00136             *item++ = m_tolerance;
00137             *item++ = m_yd;
00138             *item++ = m_yddot;
00139             *item++ = m_alpha;
00140             memcpy(item, &m_chi[0], 6*sizeof(e_scalar));
00141         }
00142         m_distCTs = timestamp;
00143     }
00144 }
00145 
00146 bool Distance::popDist(CacheTS timestamp)
00147 {
00148     if (m_distCCh >= 0) {
00149         double *item = (double*)m_cache->getPreviousCacheItem(this, m_distCCh, &timestamp);
00150         if (item && timestamp != m_distCTs) {
00151             m_values.feedback = m_K = *item++;
00152             m_values.tolerance = m_tolerance = *item++;
00153             m_yd = *item++;
00154             m_yddot = *item++;
00155             m_values.alpha = m_alpha = *item++;
00156             memcpy(&m_chi[0], item, 6*sizeof(e_scalar));
00157             m_distCTs = timestamp;
00158             m_Wy(0) = m_alpha/*/(m_tolerance*m_K)*/;
00159             updateJacobian();
00160         }
00161         return (item) ? true : false;
00162     }
00163     return true;
00164 }
00165 
00166 void Distance::pushCache(const Timestamp& timestamp)
00167 {
00168     if (!timestamp.substep && timestamp.cache)
00169         pushDist(timestamp.cacheTimestamp);
00170 }
00171 
00172 void Distance::updateKinematics(const Timestamp& timestamp)
00173 {
00174     if (timestamp.interpolate) {
00175         //the internal pose and Jf is already up to date (see model_update)
00176         //update the desired output based on yddot
00177         if (timestamp.substep) {
00178             m_yd += m_yddot*timestamp.realTimestep;
00179             if (m_yd < KDL::epsilon)
00180                 m_yd = KDL::epsilon;
00181         } else {
00182             m_yd = m_nextyd;
00183             m_yddot = m_nextyddot;
00184         }
00185     }
00186     pushCache(timestamp);
00187 }
00188 
00189 void Distance::updateJacobian()
00190 {
00191     for(unsigned int i=0;i<6;i++)
00192         m_chiKdl(i)=m_chi(i);
00193 
00194     m_fksolver->JntToCart(m_chiKdl,m_internalPose);
00195     m_jacsolver->JntToJac(m_chiKdl,m_jac);
00196     changeRefPoint(m_jac,-m_internalPose.p,m_jac);
00197     for(unsigned int i=0;i<6;i++)
00198         for(unsigned int j=0;j<6;j++)
00199             m_Jf(i,j)=m_jac(i,j);
00200 }
00201 
00202 bool Distance::setControlParameters(struct ConstraintValues* _values, unsigned int _nvalues, double timestep)
00203 {
00204     int action = 0;
00205     int i;
00206     ConstraintSingleValue* _data;
00207 
00208     while (_nvalues > 0) {
00209         if (_values->id == ID_DISTANCE) {
00210             if ((_values->action & ACT_ALPHA) && _values->alpha >= 0.0) {
00211                 m_alpha = _values->alpha;
00212                 action |= ACT_ALPHA;
00213             }
00214             if ((_values->action & ACT_TOLERANCE) && _values->tolerance > KDL::epsilon) {
00215                 m_tolerance = _values->tolerance;
00216                 action |= ACT_TOLERANCE;
00217             }
00218             if ((_values->action & ACT_FEEDBACK) && _values->feedback > KDL::epsilon) {
00219                 m_K = _values->feedback;
00220                 action |= ACT_FEEDBACK;
00221             }
00222             for (_data = _values->values, i=0; i<_values->number; i++, _data++) {
00223                 if (_data->id == ID_DISTANCE) {
00224                     switch (_data->action & (ACT_VALUE|ACT_VELOCITY)) {
00225                     case 0:
00226                         // no indication, keep current values
00227                         break;
00228                     case ACT_VELOCITY:
00229                         // only the velocity is given estimate the new value by integration
00230                         _data->yd = m_yd+_data->yddot*timestep;
00231                         // walkthrough for negative value correction
00232                     case ACT_VALUE:
00233                         // only the value is given, estimate the velocity from previous value
00234                         if (_data->yd < KDL::epsilon)
00235                             _data->yd = KDL::epsilon;
00236                         m_nextyd = _data->yd;
00237                         // if the user sets the value, we assume future velocity is zero
00238                         // (until the user changes the value again)
00239                         m_nextyddot = (_data->action & ACT_VALUE) ? 0.0 : _data->yddot;
00240                         if (timestep>0.0) {
00241                             m_yddot = (_data->yd-m_yd)/timestep;
00242                         } else {
00243                             // allow the user to change target instantenously when this function
00244                             // if called from setControlParameter with timestep = 0
00245                             m_yddot = m_nextyddot;
00246                             m_yd = m_nextyd;
00247                         }
00248                         break;
00249                     case (ACT_VALUE|ACT_VELOCITY):
00250                         // the user should not set the value and velocity at the same time.
00251                         // In this case, we will assume that he want to set the future value
00252                         // and we compute the current value to match the velocity
00253                         if (_data->yd < KDL::epsilon)
00254                             _data->yd = KDL::epsilon;
00255                         m_yd = _data->yd - _data->yddot*timestep;
00256                         if (m_yd < KDL::epsilon)
00257                             m_yd = KDL::epsilon;
00258                         m_nextyd = _data->yd;
00259                         m_nextyddot = _data->yddot;
00260                         if (timestep>0.0) {
00261                             m_yddot = (_data->yd-m_yd)/timestep;
00262                         } else {
00263                             m_yd = m_nextyd;
00264                             m_yddot = m_nextyddot;
00265                         }
00266                         break;
00267                     }
00268                 }
00269             }
00270         }
00271         _nvalues--;
00272         _values++;
00273     }
00274     if (action & (ACT_TOLERANCE|ACT_FEEDBACK|ACT_ALPHA)) {
00275         // recompute the weight
00276         m_Wy(0) = m_alpha/*/(m_tolerance*m_K)*/;
00277     }
00278     return true;
00279 }
00280 
00281 const ConstraintValues* Distance::getControlParameters(unsigned int* _nvalues)
00282 {
00283     *(double*)&m_data.y = m_chi(2);
00284     *(double*)&m_data.ydot = m_ydot(0);
00285     m_data.yd = m_yd;
00286     m_data.yddot = m_yddot;
00287     m_data.action = 0;
00288     m_values.action = 0;
00289     if (_nvalues) 
00290         *_nvalues=1; 
00291     return &m_values; 
00292 }
00293 
00294 void Distance::updateControlOutput(const Timestamp& timestamp)
00295 {
00296     bool cacheAvail = true;
00297     if (!timestamp.substep) {
00298         if (!timestamp.reiterate)
00299             cacheAvail = popDist(timestamp.cacheTimestamp);
00300     }
00301     if (m_constraintCallback && (m_substep || (!timestamp.reiterate && !timestamp.substep))) {
00302         // initialize first callback the application to get the current values
00303         *(double*)&m_data.y = m_chi(2);
00304         *(double*)&m_data.ydot = m_ydot(0);
00305         m_data.yd = m_yd;
00306         m_data.yddot = m_yddot;
00307         m_data.action = 0;
00308         m_values.action = 0;
00309         if ((*m_constraintCallback)(timestamp, &m_values, 1, m_constraintParam)) {
00310             setControlParameters(&m_values, 1, timestamp.realTimestep);
00311         }
00312     }
00313     if (!cacheAvail || !timestamp.interpolate) {
00314         // first position in cache: set the desired output immediately as we cannot interpolate
00315         m_yd = m_nextyd;
00316         m_yddot = m_nextyddot;
00317     }
00318     double error = m_yd-m_chi(2);
00319     if (KDL::Norm(error) > m_maxerror)
00320         error = KDL::sign(error)*m_maxerror;
00321     m_ydot(0)=m_yddot+m_K*error;
00322 }
00323 
00324 }