doxygen: intern/itasc tagged
[blender.git] / intern / itasc / Scene.cpp
1 /** \file itasc/Scene.cpp
2  *  \ingroup itasc
3  */
4 /* $Id$
5  * Scene.cpp
6  *
7  *  Created on: Jan 5, 2009
8  *      Author: rubensmits
9  */
10
11 #include "Scene.hpp"
12 #include "ControlledObject.hpp"
13 #include "kdl/utilities/svd_eigen_HH.hpp"
14 #include <cstdio>
15
16 namespace iTaSC {
17
18 class SceneLock : public ControlledObject::JointLockCallback {
19 private:
20         Scene* m_scene;
21         Range  m_qrange;
22
23 public:
24         SceneLock(Scene* scene) :
25           m_scene(scene), m_qrange(0,0) {}
26         virtual ~SceneLock() {}
27
28         void setRange(Range& range)
29         {
30                 m_qrange = range;
31         }
32         // lock a joint, no need to update output
33         virtual void lockJoint(unsigned int q_nr, unsigned int ndof)
34         {
35                 q_nr += m_qrange.start;
36                 project(m_scene->m_Wq, Range(q_nr, ndof), m_qrange).setZero();
37         }
38         // lock a joint and update output in view of reiteration
39         virtual void lockJoint(unsigned int q_nr, unsigned int ndof, double* qdot)
40         {
41                 q_nr += m_qrange.start;
42                 project(m_scene->m_Wq, Range(q_nr, ndof), m_qrange).setZero();
43                 // update the ouput vector so that the movement of this joint will be 
44                 // taken into account and we can put the joint back in its initial position
45                 // which means that the jacobian doesn't need to be changed
46                 for (unsigned int i=0 ;i<ndof ; ++i, ++q_nr) {
47                         m_scene->m_ydot -= m_scene->m_A.col(q_nr)*qdot[i];
48                 }
49         }
50 };
51
52 Scene::Scene():
53         m_A(), m_B(), m_Atemp(), m_Wq(), m_Jf(), m_Jq(), m_Ju(), m_Cf(), m_Cq(), m_Jf_inv(),
54         m_Vf(),m_Uf(), m_Wy(), m_ydot(), m_qdot(), m_xdot(), m_Sf(),m_tempf(),
55         m_ncTotal(0),m_nqTotal(0),m_nuTotal(0),m_nsets(0),
56         m_solver(NULL),m_cache(NULL) 
57 {
58         m_minstep = 0.01;
59         m_maxstep = 0.06;
60 }
61
62 Scene::~Scene() 
63 {
64         ConstraintMap::iterator constraint_it;
65         while ((constraint_it = constraints.begin()) != constraints.end()) {
66                 delete constraint_it->second;
67                 constraints.erase(constraint_it);
68         }
69         ObjectMap::iterator object_it;
70         while ((object_it = objects.begin()) != objects.end()) {
71                 delete object_it->second;
72                 objects.erase(object_it);
73         }
74 }
75
76 bool Scene::setParam(SceneParam paramId, double value)
77 {
78         switch (paramId) {
79         case MIN_TIMESTEP:
80                 m_minstep = value;
81                 break;
82         case MAX_TIMESTEP:              
83                 m_maxstep = value;
84                 break;
85         default:
86                 return false;
87         }
88         return true;
89 }
90
91 bool Scene::addObject(const std::string& name, Object* object, UncontrolledObject* base, const std::string& baseFrame)
92 {
93         // finalize the object before adding
94         object->finalize();
95     //Check if Object is controlled or uncontrolled.
96     if(object->getType()==Object::Controlled){
97                 int baseFrameIndex = base->addEndEffector(baseFrame);
98                 if (baseFrameIndex < 0)
99                         return false;
100                 std::pair<ObjectMap::iterator, bool> result;
101                 if (base->getNrOfCoordinates() == 0) {
102                         // base is fixed object, no coordinate range
103                         result = objects.insert(ObjectMap::value_type(
104                                         name, new Object_struct(object,base,baseFrameIndex,
105                                                 Range(m_nqTotal,object->getNrOfCoordinates()),
106                                                 Range(m_ncTotal,((ControlledObject*)object)->getNrOfConstraints()),
107                                                 Range(0,0))));
108                 } else {
109                         // base is a moving object, must be in list already
110                     ObjectMap::iterator base_it;
111                         for (base_it=objects.begin(); base_it != objects.end(); base_it++) {
112                                 if (base_it->second->object == base)
113                                         break;
114                         }
115                         if (base_it == objects.end())
116                                 return false;
117                         result = objects.insert(ObjectMap::value_type(
118                                         name, new Object_struct(object,base,baseFrameIndex,
119                                                 Range(m_nqTotal,object->getNrOfCoordinates()),
120                                                 Range(m_ncTotal,((ControlledObject*)object)->getNrOfConstraints()),
121                                                 base_it->second->coordinaterange)));
122                 }
123                 if (!result.second) {
124                         return false;
125                 }
126         m_nqTotal+=object->getNrOfCoordinates();
127         m_ncTotal+=((ControlledObject*)object)->getNrOfConstraints();
128         return true;
129     }
130     if(object->getType()==Object::UnControlled){
131                 if ((WorldObject*)base != &Object::world)
132                         return false;
133                 std::pair<ObjectMap::iterator,bool> result = objects.insert(ObjectMap::value_type(
134                         name,new Object_struct(object,base,0,
135                                                 Range(0,0),
136                                                 Range(0,0),
137                                                 Range(m_nuTotal,object->getNrOfCoordinates()))));
138         if(!result.second)
139             return false;
140         m_nuTotal+=object->getNrOfCoordinates();
141         return true;
142     }
143     return false;
144 }
145
146 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)
147 {
148     //Check if objects exist:
149     ObjectMap::iterator object1_it = objects.find(object1);
150     ObjectMap::iterator object2_it = objects.find(object2);
151     if(object1_it==objects.end()||object2_it==objects.end())
152         return false;
153         int ee1_index = object1_it->second->object->addEndEffector(ee1);
154         int ee2_index = object2_it->second->object->addEndEffector(ee2);
155         if (ee1_index < 0 || ee2_index < 0)
156                 return false;
157         std::pair<ConstraintMap::iterator,bool> result = 
158                 constraints.insert(ConstraintMap::value_type(name,new ConstraintSet_struct(
159                         task,object1_it,ee1_index,object2_it,ee2_index,
160                         Range(m_ncTotal,task->getNrOfConstraints()),Range(6*m_nsets,6))));
161     if(!result.second)
162         return false;
163     m_ncTotal+=task->getNrOfConstraints();
164     m_nsets+=1;
165     return true;
166 }
167
168 bool Scene::addSolver(Solver* _solver){
169     if(m_solver==NULL){
170         m_solver=_solver;
171         return true;
172     }
173     else
174         return false;
175 }
176
177 bool Scene::addCache(Cache* _cache){
178     if(m_cache==NULL){
179         m_cache=_cache;
180         return true;
181     }
182     else
183         return false;
184 }
185
186 bool Scene::initialize(){
187
188     //prepare all matrices:
189         if (m_ncTotal == 0 || m_nqTotal == 0 || m_nsets == 0)
190                 return false;
191
192     m_A = e_zero_matrix(m_ncTotal,m_nqTotal);
193         if (m_nuTotal > 0) {
194                 m_B = e_zero_matrix(m_ncTotal,m_nuTotal);
195                 m_xdot = e_zero_vector(m_nuTotal);
196                 m_Ju = e_zero_matrix(6*m_nsets,m_nuTotal);
197         }
198     m_Atemp = e_zero_matrix(m_ncTotal,6*m_nsets);
199     m_ydot = e_zero_vector(m_ncTotal);
200     m_qdot = e_zero_vector(m_nqTotal);
201     m_Wq = e_zero_matrix(m_nqTotal,m_nqTotal);
202     m_Wy = e_zero_vector(m_ncTotal);
203     m_Jq = e_zero_matrix(6*m_nsets,m_nqTotal);
204     m_Jf = e_zero_matrix(6*m_nsets,6*m_nsets);
205     m_Jf_inv = m_Jf;
206     m_Cf = e_zero_matrix(m_ncTotal,m_Jf.rows());
207     m_Cq = e_zero_matrix(m_ncTotal,m_nqTotal);
208
209     bool result=true;
210         // finalize all objects
211         for (ObjectMap::iterator it=objects.begin(); it!=objects.end(); ++it) {
212                 Object_struct* os = it->second;
213
214                 os->object->initCache(m_cache);
215                 if (os->constraintrange.count > 0)
216                         project(m_Cq,os->constraintrange,os->jointrange) = (((ControlledObject*)(os->object))->getCq());
217         }
218
219         m_ytask.resize(m_ncTotal);
220         bool toggle=true;
221         int cnt = 0;
222     //Initialize all ConstraintSets:
223     for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
224         //Calculate the external pose:
225                 ConstraintSet_struct* cs = it->second;
226                 Frame external_pose;
227                 getConstraintPose(cs->task, cs, external_pose);
228         result&=cs->task->initialise(external_pose);
229                 cs->task->initCache(m_cache);
230                 for (int i=0; i<cs->constraintrange.count; i++, cnt++) {
231                         m_ytask[cnt] = toggle;
232                 }
233                 toggle = !toggle;
234                 project(m_Cf,cs->constraintrange,cs->featurerange)=cs->task->getCf();
235     }
236
237     if(m_solver!=NULL)
238         m_solver->init(m_nqTotal,m_ncTotal,m_ytask);
239     else
240         return false;
241
242
243     return result;
244 }
245
246 bool Scene::getConstraintPose(ConstraintSet* constraint, void *_param, KDL::Frame& _pose)
247 {
248         // function called from constraint when they need to get the external pose
249         ConstraintSet_struct* cs = (ConstraintSet_struct*)_param;
250         // verification, the pointer MUST match
251         assert (constraint == cs->task);
252         Object_struct* ob1 = cs->object1->second;
253         Object_struct* ob2 = cs->object2->second;
254         //Calculate the external pose:
255         _pose=(ob1->base->getPose(ob1->baseFrameIndex)*ob1->object->getPose(cs->ee1index)).Inverse()*(ob2->base->getPose(ob2->baseFrameIndex)*ob2->object->getPose(cs->ee2index));
256         return true;
257 }
258
259 bool Scene::update(double timestamp, double timestep, unsigned int numsubstep, bool reiterate, bool cache, bool interpolate)
260 {
261         // we must have valid timestep and timestamp
262         if (timestamp < KDL::epsilon || timestep < 0.0)
263                 return false;
264         Timestamp ts;
265         ts.realTimestamp = timestamp;
266         // initially we start with the full timestep to allow velocity estimation over the full interval
267         ts.realTimestep = timestep;
268         setCacheTimestamp(ts);
269         ts.substep = 0;
270         // for reiteration don't load cache
271         // reiteration=additional iteration with same timestamp if application finds the convergence not good enough
272         ts.reiterate = (reiterate) ? 1 : 0;
273         ts.interpolate = (interpolate) ? 1 : 0;
274         ts.cache = (cache) ? 1 : 0;
275         ts.update = 1;
276         ts.numstep = (numsubstep & 0xFF);
277         bool autosubstep = (numsubstep == 0) ? true : false;
278         if (numsubstep < 1)
279                 numsubstep = 1;
280         double timesubstep = timestep/numsubstep;
281         double timeleft = timestep;
282
283         if (timeleft == 0.0) {
284                 // this special case correspond to a request to cache data
285                 for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it){
286                         it->second->object->pushCache(ts);
287                 }
288                 //Update the Constraints
289                 for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
290                         it->second->task->pushCache(ts);
291                 }
292                 return true;
293         }
294
295         double maxqdot;
296         e_scalar nlcoef;
297         SceneLock lockCallback(this);
298         Frame external_pose;
299         bool locked;
300
301         // initially we keep timestep unchanged so that update function compute the velocity over
302         while (numsubstep > 0) {
303                 // get objects
304                 for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it) {
305                         Object_struct* os = it->second;
306                         if (os->object->getType()==Object::Controlled) {
307                                 ((ControlledObject*)(os->object))->updateControlOutput(ts);
308                                 if (os->constraintrange.count > 0) {
309                                         project(m_ydot, os->constraintrange) = ((ControlledObject*)(os->object))->getControlOutput();
310                                         project(m_Wy, os->constraintrange) = ((ControlledObject*)(os->object))->getWy();
311                                         // project(m_Cq,os->constraintrange,os->jointrange) = (((ControlledObject*)(os->object))->getCq());
312                                 }
313                                 if (os->jointrange.count > 0) {
314                                         project(m_Wq,os->jointrange,os->jointrange) = ((ControlledObject*)(os->object))->getWq();
315                                 }
316                         }
317                         if (os->object->getType()==Object::UnControlled && ((UncontrolledObject*)os->object)->getNrOfCoordinates() != 0) {
318                     ((UncontrolledObject*)(os->object))->updateCoordinates(ts);
319                                 if (!ts.substep) {
320                                         // velocity of uncontrolled object remains constant during substepping
321                                         project(m_xdot,os->coordinaterange) = ((UncontrolledObject*)(os->object))->getXudot();
322                                 }
323                         }
324                 }
325
326                 //get new Constraints values
327                 for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it) {
328                         ConstraintSet_struct* cs = it->second;
329                         Object_struct* ob1 = cs->object1->second;
330                         Object_struct* ob2 = cs->object2->second;
331
332                         if (ob1->base->updated() || ob1->object->updated() || ob2->base->updated() || ob2->object->updated()) {
333                                 // the object from which the constraint depends have changed position
334                                 // recompute the constraint pose
335                                 getConstraintPose(cs->task, cs, external_pose);
336                                 cs->task->initialise(external_pose);
337                         }
338                         cs->task->updateControlOutput(ts);
339                 project(m_ydot,cs->constraintrange)=cs->task->getControlOutput();
340                         if (!ts.substep || cs->task->substep()) {
341                                 project(m_Wy,cs->constraintrange)=(cs->task)->getWy();
342                                 //project(m_Cf,cs->constraintrange,cs->featurerange)=cs->task->getCf();
343                         }
344
345                         project(m_Jf,cs->featurerange,cs->featurerange)=cs->task->getJf();
346                         //std::cout << "Jf = " << Jf << std::endl;
347                         //Transform the reference frame of this jacobian to the world reference frame
348                         Eigen::Block<e_matrix> Jf_part = project(m_Jf,cs->featurerange,cs->featurerange);
349                         changeBase(Jf_part,ob1->base->getPose(ob1->baseFrameIndex)*ob1->object->getPose(cs->ee1index));
350                         //std::cout << "Jf_w = " << Jf << std::endl;
351
352                         //calculate the inverse of Jf
353                         KDL::svd_eigen_HH(project(m_Jf,cs->featurerange,cs->featurerange),m_Uf,m_Sf,m_Vf,m_tempf);
354                         for(unsigned int i=0;i<6;++i)
355                                 if(m_Sf(i)<KDL::epsilon)
356                                         m_Uf.col(i).setConstant(0.0);
357                                 else
358                                         m_Uf.col(i)*=(1/m_Sf(i));
359                         project(m_Jf_inv,cs->featurerange,cs->featurerange)=(m_Vf*m_Uf.transpose()).lazy();
360
361                         //Get the robotjacobian associated with this constraintset
362                         //Each jacobian is expressed in robot base frame => convert to world reference
363                         //and negate second robot because it is taken reversed when closing the loop:
364                         if(ob1->object->getType()==Object::Controlled){
365                                 project(m_Jq,cs->featurerange,ob1->jointrange) = (((ControlledObject*)(ob1->object))->getJq(cs->ee1index));
366                                 //Transform the reference frame of this jacobian to the world reference frame:
367                                 Eigen::Block<e_matrix> Jq_part = project(m_Jq,cs->featurerange,ob1->jointrange);
368                                 changeBase(Jq_part,ob1->base->getPose(ob1->baseFrameIndex));
369                                 // if the base of this object is moving, get the Ju part
370                                 if (ob1->base->getNrOfCoordinates() != 0) {
371                                         // Ju is already computed for world reference frame
372                                         project(m_Ju,cs->featurerange,ob1->coordinaterange)=ob1->base->getJu(ob1->baseFrameIndex);
373                                 }
374                         } else if (ob1->object->getType() == Object::UnControlled && ((UncontrolledObject*)ob1->object)->getNrOfCoordinates() != 0) {
375                                 // object1 is uncontrolled moving object
376                                 project(m_Ju,cs->featurerange,ob1->coordinaterange)=((UncontrolledObject*)ob1->object)->getJu(cs->ee1index);
377                         }
378                         if(ob2->object->getType()==Object::Controlled){
379                                 //Get the robotjacobian associated with this constraintset
380                                 // process a special case where object2 and object1 are equal but using different end effector
381                                 if (ob1->object == ob2->object) {
382                                         // we must create a temporary matrix
383                                         e_matrix JqTemp(((ControlledObject*)(ob2->object))->getJq(cs->ee2index));
384                                         //Transform the reference frame of this jacobian to the world reference frame:
385                                         changeBase(JqTemp,ob2->base->getPose(ob2->baseFrameIndex));
386                                         // substract in place
387                                         project(m_Jq,cs->featurerange,ob2->jointrange) -= JqTemp;
388                                 } else {
389                                         project(m_Jq,cs->featurerange,ob2->jointrange) = -(((ControlledObject*)(ob2->object))->getJq(cs->ee2index));
390                                         //Transform the reference frame of this jacobian to the world reference frame:
391                                         Eigen::Block<e_matrix> Jq_part = project(m_Jq,cs->featurerange,ob2->jointrange);
392                                         changeBase(Jq_part,ob2->base->getPose(ob2->baseFrameIndex));
393                                 }
394                                 if (ob2->base->getNrOfCoordinates() != 0) {
395                                         // if base is the same as first object or first object base, 
396                                         // that portion of m_Ju has been set already => substract inplace
397                                         if (ob2->base == ob1->base || ob2->base == ob1->object) {
398                                                 project(m_Ju,cs->featurerange,ob2->coordinaterange) -= ob2->base->getJu(ob2->baseFrameIndex);
399                                         } else {
400                                                 project(m_Ju,cs->featurerange,ob2->coordinaterange) = -ob2->base->getJu(ob2->baseFrameIndex);
401                                         }
402                                 }
403                         } else if (ob2->object->getType() == Object::UnControlled && ((UncontrolledObject*)ob2->object)->getNrOfCoordinates() != 0) {
404                                 if (ob2->object == ob1->base || ob2->object == ob1->object) {
405                                         project(m_Ju,cs->featurerange,ob2->coordinaterange) -= ((UncontrolledObject*)ob2->object)->getJu(cs->ee2index);
406                                 } else {
407                                         project(m_Ju,cs->featurerange,ob2->coordinaterange) = -((UncontrolledObject*)ob2->object)->getJu(cs->ee2index);
408                                 }
409                         }
410                 }
411
412             //Calculate A
413                 m_Atemp=(m_Cf*m_Jf_inv).lazy();
414                 m_A = m_Cq-(m_Atemp*m_Jq).lazy();
415                 if (m_nuTotal > 0) {
416                         m_B=(m_Atemp*m_Ju).lazy();
417                         m_ydot += (m_B*m_xdot).lazy();
418                 }
419
420                 //Call the solver with A, Wq, Wy, ydot to solver qdot:
421                 if(!m_solver->solve(m_A,m_Wy,m_ydot,m_Wq,m_qdot,nlcoef))
422                         // this should never happen
423                         return false;
424                 //send result to the objects
425                 for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it) {
426                         Object_struct* os = it->second;
427                         if(os->object->getType()==Object::Controlled)
428                                 ((ControlledObject*)(os->object))->setJointVelocity(project(m_qdot,os->jointrange));
429                 }
430                 // compute the constraint velocity
431                 for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
432                         ConstraintSet_struct* cs = it->second;
433                         Object_struct* ob1 = cs->object1->second;
434                         Object_struct* ob2 = cs->object2->second;
435                         //Calculate the twist of the world reference frame due to the robots (Jq*qdot+Ju*chiudot):
436                         e_vector6 external_vel = e_zero_vector(6);
437                         if (ob1->jointrange.count > 0)
438                                 external_vel += (project(m_Jq,cs->featurerange,ob1->jointrange)*project(m_qdot,ob1->jointrange)).lazy();
439                         if (ob2->jointrange.count > 0)
440                                 external_vel += (project(m_Jq,cs->featurerange,ob2->jointrange)*project(m_qdot,ob2->jointrange)).lazy();
441                         if (ob1->coordinaterange.count > 0)
442                                 external_vel += (project(m_Ju,cs->featurerange,ob1->coordinaterange)*project(m_xdot,ob1->coordinaterange)).lazy();
443                         if (ob2->coordinaterange.count > 0)
444                                 external_vel += (project(m_Ju,cs->featurerange,ob2->coordinaterange)*project(m_xdot,ob2->coordinaterange)).lazy();
445                         //the twist caused by the constraint must be opposite because of the closed loop
446                         //estimate the velocity of the joints using the inverse jacobian
447                         e_vector6 estimated_chidot = project(m_Jf_inv,cs->featurerange,cs->featurerange)*(-external_vel);
448                         cs->task->setJointVelocity(estimated_chidot);
449                 }
450
451                 if (autosubstep) {
452                         // automatic computing of substep based on maximum joint change
453                         // and joint limit gain variation
454                         // We will pass the joint velocity to each object and they will recommend a maximum timestep
455                         timesubstep = timeleft;
456                         // get armature max joint velocity to estimate the maximum duration of integration
457                         maxqdot = m_qdot.cwise().abs().maxCoeff();
458                         double maxsubstep = nlcoef*m_maxstep;
459                         if (maxsubstep < m_minstep)
460                                 maxsubstep = m_minstep;
461                         if (timesubstep > maxsubstep)
462                                 timesubstep = maxsubstep;
463                         for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it){
464                                 Object_struct* os = it->second;
465                                 if(os->object->getType()==Object::Controlled)
466                                         ((ControlledObject*)(os->object))->getMaxTimestep(timesubstep);
467                         }
468                         for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
469                                 ConstraintSet_struct* cs = it->second;
470                                 cs->task->getMaxTimestep(timesubstep);
471                         }
472                         // use substep that are even dividers of timestep for more regularity
473                         maxsubstep = 2.0*floor(timestep/2.0/timesubstep-0.66666);
474                         timesubstep = (maxsubstep < 0.0) ? timestep : timestep/(2.0+maxsubstep);
475                         if (timesubstep >= timeleft-(m_minstep/2.0)) {
476                                 timesubstep = timeleft;
477                                 numsubstep = 1;
478                                 timeleft = 0.;
479                         } else {
480                                 numsubstep = 2;
481                                 timeleft -= timesubstep;
482                         }
483                 }
484                 if (numsubstep > 1) {
485                         ts.substep = 1;
486                 } else {
487                         // set substep to false for last iteration so that controlled output 
488                         // can be updated in updateKinematics() and model_update)() before next call to Secne::update()
489                         ts.substep = 0;
490                 }
491                 // change timestep so that integration is done correctly
492                 ts.realTimestep = timesubstep;
493
494                 do {
495                         ObjectMap::iterator it;
496                         Object_struct* os;
497                         locked = false;
498                         for(it=objects.begin();it!=objects.end();++it){
499                                 os = it->second;
500                                 if (os->object->getType()==Object::Controlled) {
501                                         lockCallback.setRange(os->jointrange);
502                                         if (((ControlledObject*)os->object)->updateJoint(ts, lockCallback)) {
503                                                 // this means one of the joint was locked and we must rerun
504                                                 // the solver to update the remaining joints
505                                                 locked = true;
506                                                 break;
507                                         }
508                                 }
509                         }
510                         if (locked) {
511                                 // Some rows of m_Wq have been cleared so that the corresponding joint will not move
512                                 if(!m_solver->solve(m_A,m_Wy,m_ydot,m_Wq,m_qdot,nlcoef))
513                                         // this should never happen
514                                         return false;
515
516                                 //send result to the objects
517                                 for(it=objects.begin();it!=objects.end();++it) {
518                                         os = it->second;
519                                         if(os->object->getType()==Object::Controlled)
520                                                 ((ControlledObject*)(os->object))->setJointVelocity(project(m_qdot,os->jointrange));
521                                 }
522                         }
523                 } while (locked);
524
525                 //Update the Objects
526                 for(ObjectMap::iterator it=objects.begin();it!=objects.end();++it){
527                         it->second->object->updateKinematics(ts);
528                         // mark this object not updated since the constraint will be updated anyway
529                         // this flag is only useful to detect external updates
530                         it->second->object->updated(false);
531                 }
532                 //Update the Constraints
533                 for(ConstraintMap::iterator it=constraints.begin();it!=constraints.end();++it){
534                         ConstraintSet_struct* cs = it->second;
535                         //Calculate the external pose:
536                         getConstraintPose(cs->task, cs, external_pose);
537                         cs->task->modelUpdate(external_pose,ts);
538                         // update the constraint output and cache
539                         cs->task->updateKinematics(ts);
540                 }
541                 numsubstep--;
542         }
543         return true;
544 }
545
546 }