Blender V2.61 - r43446

Scene.cpp

Go to the documentation of this file.
00001 
00004 /*
00005  * Scene.cpp
00006  *
00007  *  Created on: Jan 5, 2009
00008  *      Author: rubensmits
00009  */
00010 
00011 #include "Scene.hpp"
00012 #include "ControlledObject.hpp"
00013 #include "kdl/utilities/svd_eigen_HH.hpp"
00014 #include <cstdio>
00015 
00016 namespace iTaSC {
00017 
00018 class SceneLock : public ControlledObject::JointLockCallback {
00019 private:
00020     Scene* m_scene;
00021     Range  m_qrange;
00022 
00023 public:
00024     SceneLock(Scene* scene) :
00025       m_scene(scene), m_qrange(0,0) {}
00026     virtual ~SceneLock() {}
00027 
00028     void setRange(Range& range)
00029     {
00030         m_qrange = range;
00031     }
00032     // lock a joint, no need to update output
00033     virtual void lockJoint(unsigned int q_nr, unsigned int ndof)
00034     {
00035         q_nr += m_qrange.start;
00036         project(m_scene->m_Wq, Range(q_nr, ndof), m_qrange).setZero();
00037     }
00038     // lock a joint and update output in view of reiteration
00039     virtual void lockJoint(unsigned int q_nr, unsigned int ndof, double* qdot)
00040     {
00041         q_nr += m_qrange.start;
00042         project(m_scene->m_Wq, Range(q_nr, ndof), m_qrange).setZero();
00043         // update the ouput vector so that the movement of this joint will be 
00044         // taken into account and we can put the joint back in its initial position
00045         // which means that the jacobian doesn't need to be changed
00046         for (unsigned int i=0 ;i<ndof ; ++i, ++q_nr) {
00047             m_scene->m_ydot -= m_scene->m_A.col(q_nr)*qdot[i];
00048         }
00049     }
00050 };
00051 
00052 Scene::Scene():
00053     m_A(), m_B(), m_Atemp(), m_Wq(), m_Jf(), m_Jq(), m_Ju(), m_Cf(), m_Cq(), m_Jf_inv(),
00054     m_Vf(),m_Uf(), m_Wy(), m_ydot(), m_qdot(), m_xdot(), m_Sf(),m_tempf(),
00055     m_ncTotal(0),m_nqTotal(0),m_nuTotal(0),m_nsets(0),
00056     m_solver(NULL),m_cache(NULL) 
00057 {
00058     m_minstep = 0.01;
00059     m_maxstep = 0.06;
00060 }
00061 
00062 Scene::~Scene() 
00063 {
00064     ConstraintMap::iterator constraint_it;
00065     while ((constraint_it = constraints.begin()) != constraints.end()) {
00066         delete constraint_it->second;
00067         constraints.erase(constraint_it);
00068     }
00069     ObjectMap::iterator object_it;
00070     while ((object_it = objects.begin()) != objects.end()) {
00071         delete object_it->second;
00072         objects.erase(object_it);
00073     }
00074 }
00075 
00076 bool Scene::setParam(SceneParam paramId, double value)
00077 {
00078     switch (paramId) {
00079     case MIN_TIMESTEP:
00080         m_minstep = value;
00081         break;
00082     case MAX_TIMESTEP:      
00083         m_maxstep = value;
00084         break;
00085     default:
00086         return false;
00087     }
00088     return true;
00089 }
00090 
00091 bool Scene::addObject(const std::string& name, Object* object, UncontrolledObject* base, const std::string& baseFrame)
00092 {
00093     // finalize the object before adding
00094     object->finalize();
00095     //Check if Object is controlled or uncontrolled.
00096     if(object->getType()==Object::Controlled){
00097         int baseFrameIndex = base->addEndEffector(baseFrame);
00098         if (baseFrameIndex < 0)
00099             return false;
00100         std::pair<ObjectMap::iterator, bool> result;
00101         if (base->getNrOfCoordinates() == 0) {
00102             // base is fixed object, no coordinate range
00103             result = objects.insert(ObjectMap::value_type(
00104                     name, new Object_struct(object,base,baseFrameIndex,
00105                         Range(m_nqTotal,object->getNrOfCoordinates()),
00106                         Range(m_ncTotal,((ControlledObject*)object)->getNrOfConstraints()),
00107                         Range(0,0))));
00108         } else {
00109             // base is a moving object, must be in list already
00110             ObjectMap::iterator base_it;
00111             for (base_it=objects.begin(); base_it != objects.end(); base_it++) {
00112                 if (base_it->second->object == base)
00113                     break;
00114             }
00115             if (base_it == objects.end())
00116                 return false;
00117             result = objects.insert(ObjectMap::value_type(
00118                     name, new Object_struct(object,base,baseFrameIndex,
00119                         Range(m_nqTotal,object->getNrOfCoordinates()),
00120                         Range(m_ncTotal,((ControlledObject*)object)->getNrOfConstraints()),
00121                         base_it->second->coordinaterange)));
00122         }
00123         if (!result.second) {
00124             return false;
00125         }
00126         m_nqTotal+=object->getNrOfCoordinates();
00127         m_ncTotal+=((ControlledObject*)object)->getNrOfConstraints();
00128         return true;
00129     }
00130     if(object->getType()==Object::UnControlled){
00131         if ((WorldObject*)base != &Object::world)
00132             return false;
00133         std::pair<ObjectMap::iterator,bool> result = objects.insert(ObjectMap::value_type(
00134             name,new Object_struct(object,base,0,
00135                         Range(0,0),
00136                         Range(0,0),
00137                         Range(m_nuTotal,object->getNrOfCoordinates()))));
00138         if(!result.second)
00139             return false;
00140         m_nuTotal+=object->getNrOfCoordinates();
00141         return true;
00142     }
00143     return false;
00144 }
00145 
00146 bool Scene::addConstraintSet(const std::string& name,ConstraintSet* task,const std::string& object1,const std::string& object2, const std::string& ee1, const std::string& ee2)
00147 {
00148     //Check if objects exist:
00149     ObjectMap::iterator object1_it = objects.find(object1);
00150     ObjectMap::iterator object2_it = objects.find(object2);
00151     if(object1_it==objects.end()||object2_it==objects.end())
00152         return false;
00153     int ee1_index = object1_it->second->object->addEndEffector(ee1);
00154     int ee2_index = object2_it->second->object->addEndEffector(ee2);
00155     if (ee1_index < 0 || ee2_index < 0)
00156         return false;
00157     std::pair<ConstraintMap::iterator,bool> result = 
00158         constraints.insert(ConstraintMap::value_type(name,new ConstraintSet_struct(
00159             task,object1_it,ee1_index,object2_it,ee2_index,
00160             Range(m_ncTotal,task->getNrOfConstraints()),Range(6*m_nsets,6))));
00161     if(!result.second)
00162         return false;
00163     m_ncTotal+=task->getNrOfConstraints();
00164     m_nsets+=1;
00165     return true;
00166 }
00167 
00168 bool Scene::addSolver(Solver* _solver){
00169     if(m_solver==NULL){
00170         m_solver=_solver;
00171         return true;
00172     }
00173     else
00174         return false;
00175 }
00176 
00177 bool Scene::addCache(Cache* _cache){
00178     if(m_cache==NULL){
00179         m_cache=_cache;
00180         return true;
00181     }
00182     else
00183         return false;
00184 }
00185 
00186 bool Scene::initialize(){
00187 
00188     //prepare all matrices:
00189     if (m_ncTotal == 0 || m_nqTotal == 0 || m_nsets == 0)
00190         return false;
00191 
00192     m_A = e_zero_matrix(m_ncTotal,m_nqTotal);
00193     if (m_nuTotal > 0) {
00194         m_B = e_zero_matrix(m_ncTotal,m_nuTotal);
00195         m_xdot = e_zero_vector(m_nuTotal);
00196         m_Ju = e_zero_matrix(6*m_nsets,m_nuTotal);
00197     }
00198     m_Atemp = e_zero_matrix(m_ncTotal,6*m_nsets);
00199     m_ydot = e_zero_vector(m_ncTotal);
00200     m_qdot = e_zero_vector(m_nqTotal);
00201     m_Wq = e_zero_matrix(m_nqTotal,m_nqTotal);
00202     m_Wy = e_zero_vector(m_ncTotal);
00203     m_Jq = e_zero_matrix(6*m_nsets,m_nqTotal);
00204     m_Jf = e_zero_matrix(6*m_nsets,6*m_nsets);
00205     m_Jf_inv = m_Jf;
00206     m_Cf = e_zero_matrix(m_ncTotal,m_Jf.rows());
00207     m_Cq = e_zero_matrix(m_ncTotal,m_nqTotal);
00208 
00209     bool result=true;
00210     // finalize all objects
00211     for (ObjectMap::iterator it=objects.begin(); it!=objects.end(); ++it) {
00212         Object_struct* os = it->second;
00213 
00214         os->object->initCache(m_cache);
00215         if (os->constraintrange.count > 0)
00216             project(m_Cq,os->constraintrange,os->jointrange) = (((ControlledObject*)(os->object))->getCq());
00217     }
00218 
00219     m_ytask.resize(m_ncTotal);
00220     bool toggle=true;
00221     int cnt = 0;
00222     //Initialize all ConstraintSets:
00223     for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
00224         //Calculate the external pose:
00225         ConstraintSet_struct* cs = it->second;
00226         Frame external_pose;
00227         getConstraintPose(cs->task, cs, external_pose);
00228         result&=cs->task->initialise(external_pose);
00229         cs->task->initCache(m_cache);
00230         for (int i=0; i<cs->constraintrange.count; i++, cnt++) {
00231             m_ytask[cnt] = toggle;
00232         }
00233         toggle = !toggle;
00234         project(m_Cf,cs->constraintrange,cs->featurerange)=cs->task->getCf();
00235     }
00236 
00237     if(m_solver!=NULL)
00238         m_solver->init(m_nqTotal,m_ncTotal,m_ytask);
00239     else
00240         return false;
00241 
00242 
00243     return result;
00244 }
00245 
00246 bool Scene::getConstraintPose(ConstraintSet* constraint, void *_param, KDL::Frame& _pose)
00247 {
00248     // function called from constraint when they need to get the external pose
00249     ConstraintSet_struct* cs = (ConstraintSet_struct*)_param;
00250     // verification, the pointer MUST match
00251     assert (constraint == cs->task);
00252     Object_struct* ob1 = cs->object1->second;
00253     Object_struct* ob2 = cs->object2->second;
00254     //Calculate the external pose:
00255     _pose=(ob1->base->getPose(ob1->baseFrameIndex)*ob1->object->getPose(cs->ee1index)).Inverse()*(ob2->base->getPose(ob2->baseFrameIndex)*ob2->object->getPose(cs->ee2index));
00256     return true;
00257 }
00258 
00259 bool Scene::update(double timestamp, double timestep, unsigned int numsubstep, bool reiterate, bool cache, bool interpolate)
00260 {
00261     // we must have valid timestep and timestamp
00262     if (timestamp < KDL::epsilon || timestep < 0.0)
00263         return false;
00264     Timestamp ts;
00265     ts.realTimestamp = timestamp;
00266     // initially we start with the full timestep to allow velocity estimation over the full interval
00267     ts.realTimestep = timestep;
00268     setCacheTimestamp(ts);
00269     ts.substep = 0;
00270     // for reiteration don't load cache
00271     // reiteration=additional iteration with same timestamp if application finds the convergence not good enough
00272     ts.reiterate = (reiterate) ? 1 : 0;
00273     ts.interpolate = (interpolate) ? 1 : 0;
00274     ts.cache = (cache) ? 1 : 0;
00275     ts.update = 1;
00276     ts.numstep = (numsubstep & 0xFF);
00277     bool autosubstep = (numsubstep == 0) ? true : false;
00278     if (numsubstep < 1)
00279         numsubstep = 1;
00280     double timesubstep = timestep/numsubstep;
00281     double timeleft = timestep;
00282 
00283     if (timeleft == 0.0) {
00284         // this special case correspond to a request to cache data
00285         for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it){
00286             it->second->object->pushCache(ts);
00287         }
00288         //Update the Constraints
00289         for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
00290             it->second->task->pushCache(ts);
00291         }
00292         return true;
00293     }
00294 
00295     // double maxqdot; // UNUSED
00296     e_scalar nlcoef;
00297     SceneLock lockCallback(this);
00298     Frame external_pose;
00299     bool locked;
00300 
00301     // initially we keep timestep unchanged so that update function compute the velocity over
00302     while (numsubstep > 0) {
00303         // get objects
00304         for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it) {
00305             Object_struct* os = it->second;
00306             if (os->object->getType()==Object::Controlled) {
00307                 ((ControlledObject*)(os->object))->updateControlOutput(ts);
00308                 if (os->constraintrange.count > 0) {
00309                     project(m_ydot, os->constraintrange) = ((ControlledObject*)(os->object))->getControlOutput();
00310                     project(m_Wy, os->constraintrange) = ((ControlledObject*)(os->object))->getWy();
00311                     // project(m_Cq,os->constraintrange,os->jointrange) = (((ControlledObject*)(os->object))->getCq());
00312                 }
00313                 if (os->jointrange.count > 0) {
00314                     project(m_Wq,os->jointrange,os->jointrange) = ((ControlledObject*)(os->object))->getWq();
00315                 }
00316             }
00317             if (os->object->getType()==Object::UnControlled && ((UncontrolledObject*)os->object)->getNrOfCoordinates() != 0) {
00318                 ((UncontrolledObject*)(os->object))->updateCoordinates(ts);
00319                 if (!ts.substep) {
00320                     // velocity of uncontrolled object remains constant during substepping
00321                     project(m_xdot,os->coordinaterange) = ((UncontrolledObject*)(os->object))->getXudot();
00322                 }
00323             }
00324         }
00325 
00326         //get new Constraints values
00327         for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it) {
00328             ConstraintSet_struct* cs = it->second;
00329             Object_struct* ob1 = cs->object1->second;
00330             Object_struct* ob2 = cs->object2->second;
00331 
00332             if (ob1->base->updated() || ob1->object->updated() || ob2->base->updated() || ob2->object->updated()) {
00333                 // the object from which the constraint depends have changed position
00334                 // recompute the constraint pose
00335                 getConstraintPose(cs->task, cs, external_pose);
00336                 cs->task->initialise(external_pose);
00337             }
00338             cs->task->updateControlOutput(ts);
00339             project(m_ydot,cs->constraintrange)=cs->task->getControlOutput();
00340             if (!ts.substep || cs->task->substep()) {
00341                 project(m_Wy,cs->constraintrange)=(cs->task)->getWy();
00342                 //project(m_Cf,cs->constraintrange,cs->featurerange)=cs->task->getCf();
00343             }
00344 
00345             project(m_Jf,cs->featurerange,cs->featurerange)=cs->task->getJf();
00346             //std::cout << "Jf = " << Jf << std::endl;
00347             //Transform the reference frame of this jacobian to the world reference frame
00348             Eigen::Block<e_matrix> Jf_part = project(m_Jf,cs->featurerange,cs->featurerange);
00349             changeBase(Jf_part,ob1->base->getPose(ob1->baseFrameIndex)*ob1->object->getPose(cs->ee1index));
00350             //std::cout << "Jf_w = " << Jf << std::endl;
00351 
00352             //calculate the inverse of Jf
00353             KDL::svd_eigen_HH(project(m_Jf,cs->featurerange,cs->featurerange),m_Uf,m_Sf,m_Vf,m_tempf);
00354             for(unsigned int i=0;i<6;++i)
00355                 if(m_Sf(i)<KDL::epsilon)
00356                     m_Uf.col(i).setConstant(0.0);
00357                 else
00358                     m_Uf.col(i)*=(1/m_Sf(i));
00359             project(m_Jf_inv,cs->featurerange,cs->featurerange).noalias()=m_Vf*m_Uf.transpose();
00360 
00361             //Get the robotjacobian associated with this constraintset
00362             //Each jacobian is expressed in robot base frame => convert to world reference
00363             //and negate second robot because it is taken reversed when closing the loop:
00364             if(ob1->object->getType()==Object::Controlled){
00365                 project(m_Jq,cs->featurerange,ob1->jointrange) = (((ControlledObject*)(ob1->object))->getJq(cs->ee1index));
00366                 //Transform the reference frame of this jacobian to the world reference frame:
00367                 Eigen::Block<e_matrix> Jq_part = project(m_Jq,cs->featurerange,ob1->jointrange);
00368                 changeBase(Jq_part,ob1->base->getPose(ob1->baseFrameIndex));
00369                 // if the base of this object is moving, get the Ju part
00370                 if (ob1->base->getNrOfCoordinates() != 0) {
00371                     // Ju is already computed for world reference frame
00372                     project(m_Ju,cs->featurerange,ob1->coordinaterange)=ob1->base->getJu(ob1->baseFrameIndex);
00373                 }
00374             } else if (ob1->object->getType() == Object::UnControlled && ((UncontrolledObject*)ob1->object)->getNrOfCoordinates() != 0) {
00375                 // object1 is uncontrolled moving object
00376                 project(m_Ju,cs->featurerange,ob1->coordinaterange)=((UncontrolledObject*)ob1->object)->getJu(cs->ee1index);
00377             }
00378             if(ob2->object->getType()==Object::Controlled){
00379                 //Get the robotjacobian associated with this constraintset
00380                 // process a special case where object2 and object1 are equal but using different end effector
00381                 if (ob1->object == ob2->object) {
00382                     // we must create a temporary matrix
00383                     e_matrix JqTemp(((ControlledObject*)(ob2->object))->getJq(cs->ee2index));
00384                     //Transform the reference frame of this jacobian to the world reference frame:
00385                     changeBase(JqTemp,ob2->base->getPose(ob2->baseFrameIndex));
00386                     // substract in place
00387                     project(m_Jq,cs->featurerange,ob2->jointrange) -= JqTemp;
00388                 } else {
00389                     project(m_Jq,cs->featurerange,ob2->jointrange) = -(((ControlledObject*)(ob2->object))->getJq(cs->ee2index));
00390                     //Transform the reference frame of this jacobian to the world reference frame:
00391                     Eigen::Block<e_matrix> Jq_part = project(m_Jq,cs->featurerange,ob2->jointrange);
00392                     changeBase(Jq_part,ob2->base->getPose(ob2->baseFrameIndex));
00393                 }
00394                 if (ob2->base->getNrOfCoordinates() != 0) {
00395                     // if base is the same as first object or first object base, 
00396                     // that portion of m_Ju has been set already => substract inplace
00397                     if (ob2->base == ob1->base || ob2->base == ob1->object) {
00398                         project(m_Ju,cs->featurerange,ob2->coordinaterange) -= ob2->base->getJu(ob2->baseFrameIndex);
00399                     } else {
00400                         project(m_Ju,cs->featurerange,ob2->coordinaterange) = -ob2->base->getJu(ob2->baseFrameIndex);
00401                     }
00402                 }
00403             } else if (ob2->object->getType() == Object::UnControlled && ((UncontrolledObject*)ob2->object)->getNrOfCoordinates() != 0) {
00404                 if (ob2->object == ob1->base || ob2->object == ob1->object) {
00405                     project(m_Ju,cs->featurerange,ob2->coordinaterange) -= ((UncontrolledObject*)ob2->object)->getJu(cs->ee2index);
00406                 } else {
00407                     project(m_Ju,cs->featurerange,ob2->coordinaterange) = -((UncontrolledObject*)ob2->object)->getJu(cs->ee2index);
00408                 }
00409             }
00410         }
00411 
00412         //Calculate A
00413         m_Atemp.noalias()=m_Cf*m_Jf_inv;
00414         m_A.noalias() = m_Cq-(m_Atemp*m_Jq);
00415         if (m_nuTotal > 0) {
00416             m_B.noalias()=m_Atemp*m_Ju;
00417             m_ydot.noalias() += m_B*m_xdot;
00418         }
00419 
00420         //Call the solver with A, Wq, Wy, ydot to solver qdot:
00421         if(!m_solver->solve(m_A,m_Wy,m_ydot,m_Wq,m_qdot,nlcoef))
00422             // this should never happen
00423             return false;
00424         //send result to the objects
00425         for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it) {
00426             Object_struct* os = it->second;
00427             if(os->object->getType()==Object::Controlled)
00428                 ((ControlledObject*)(os->object))->setJointVelocity(project(m_qdot,os->jointrange));
00429         }
00430         // compute the constraint velocity
00431         for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
00432             ConstraintSet_struct* cs = it->second;
00433             Object_struct* ob1 = cs->object1->second;
00434             Object_struct* ob2 = cs->object2->second;
00435             //Calculate the twist of the world reference frame due to the robots (Jq*qdot+Ju*chiudot):
00436             e_vector6 external_vel = e_zero_vector(6);
00437             if (ob1->jointrange.count > 0)
00438                 external_vel.noalias() += (project(m_Jq,cs->featurerange,ob1->jointrange)*project(m_qdot,ob1->jointrange));
00439             if (ob2->jointrange.count > 0)
00440                 external_vel.noalias() += (project(m_Jq,cs->featurerange,ob2->jointrange)*project(m_qdot,ob2->jointrange));
00441             if (ob1->coordinaterange.count > 0)
00442                 external_vel.noalias() += (project(m_Ju,cs->featurerange,ob1->coordinaterange)*project(m_xdot,ob1->coordinaterange));
00443             if (ob2->coordinaterange.count > 0)
00444                 external_vel.noalias() += (project(m_Ju,cs->featurerange,ob2->coordinaterange)*project(m_xdot,ob2->coordinaterange));
00445             //the twist caused by the constraint must be opposite because of the closed loop
00446             //estimate the velocity of the joints using the inverse jacobian
00447             e_vector6 estimated_chidot = project(m_Jf_inv,cs->featurerange,cs->featurerange)*(-external_vel);
00448             cs->task->setJointVelocity(estimated_chidot);
00449         }
00450 
00451         if (autosubstep) {
00452             // automatic computing of substep based on maximum joint change
00453             // and joint limit gain variation
00454             // We will pass the joint velocity to each object and they will recommend a maximum timestep
00455             timesubstep = timeleft;
00456             // get armature max joint velocity to estimate the maximum duration of integration
00457             // maxqdot = m_qdot.cwise().abs().maxCoeff(); // UNUSED
00458             double maxsubstep = nlcoef*m_maxstep;
00459             if (maxsubstep < m_minstep)
00460                 maxsubstep = m_minstep;
00461             if (timesubstep > maxsubstep)
00462                 timesubstep = maxsubstep;
00463             for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it){
00464                 Object_struct* os = it->second;
00465                 if(os->object->getType()==Object::Controlled)
00466                     ((ControlledObject*)(os->object))->getMaxTimestep(timesubstep);
00467             }
00468             for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
00469                 ConstraintSet_struct* cs = it->second;
00470                 cs->task->getMaxTimestep(timesubstep);
00471             }
00472             // use substep that are even dividers of timestep for more regularity
00473             maxsubstep = 2.0*floor(timestep/2.0/timesubstep-0.66666);
00474             timesubstep = (maxsubstep < 0.0) ? timestep : timestep/(2.0+maxsubstep);
00475             if (timesubstep >= timeleft-(m_minstep/2.0)) {
00476                 timesubstep = timeleft;
00477                 numsubstep = 1;
00478                 timeleft = 0.;
00479             } else {
00480                 numsubstep = 2;
00481                 timeleft -= timesubstep;
00482             }
00483         }
00484         if (numsubstep > 1) {
00485             ts.substep = 1;
00486         } else {
00487             // set substep to false for last iteration so that controlled output 
00488             // can be updated in updateKinematics() and model_update)() before next call to Secne::update()
00489             ts.substep = 0;
00490         }
00491         // change timestep so that integration is done correctly
00492         ts.realTimestep = timesubstep;
00493 
00494         do {
00495             ObjectMap::iterator it;
00496             Object_struct* os;
00497             locked = false;
00498             for(it=objects.begin();it!=objects.end();++it){
00499                 os = it->second;
00500                 if (os->object->getType()==Object::Controlled) {
00501                     lockCallback.setRange(os->jointrange);
00502                     if (((ControlledObject*)os->object)->updateJoint(ts, lockCallback)) {
00503                         // this means one of the joint was locked and we must rerun
00504                         // the solver to update the remaining joints
00505                         locked = true;
00506                         break;
00507                     }
00508                 }
00509             }
00510             if (locked) {
00511                 // Some rows of m_Wq have been cleared so that the corresponding joint will not move
00512                 if(!m_solver->solve(m_A,m_Wy,m_ydot,m_Wq,m_qdot,nlcoef))
00513                     // this should never happen
00514                     return false;
00515 
00516                 //send result to the objects
00517                 for(it=objects.begin();it!=objects.end();++it) {
00518                     os = it->second;
00519                     if(os->object->getType()==Object::Controlled)
00520                         ((ControlledObject*)(os->object))->setJointVelocity(project(m_qdot,os->jointrange));
00521                 }
00522             }
00523         } while (locked);
00524 
00525         //Update the Objects
00526         for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it){
00527             it->second->object->updateKinematics(ts);
00528             // mark this object not updated since the constraint will be updated anyway
00529             // this flag is only useful to detect external updates
00530             it->second->object->updated(false);
00531         }
00532         //Update the Constraints
00533         for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
00534             ConstraintSet_struct* cs = it->second;
00535             //Calculate the external pose:
00536             getConstraintPose(cs->task, cs, external_pose);
00537             cs->task->modelUpdate(external_pose,ts);
00538             // update the constraint output and cache
00539             cs->task->updateKinematics(ts);
00540         }
00541         numsubstep--;
00542     }
00543     return true;
00544 }
00545 
00546 }