1 /*
2  * PURPOSE:
3  *   Class representing an articulated rigid body. Stores the body's
4  *   current state, allows forces and torques to be set, handles
5  *   timestepping and implements Featherstone's algorithm.
6  *
7  * COPYRIGHT:
8  *   Copyright (C) Stephen Thompson, <stephen@solarflare.org.uk>, 2011-2013
9  *   Portions written By Erwin Coumans: connection to LCP solver, various multibody constraints, replacing Eigen math library by Bullet LinearMath and a dedicated 6x6 matrix inverse (solveImatrix)
10  *   Portions written By Jakub Stepien: support for multi-DOF constraints, introduction of spatial algebra and several other improvements
11 
12  This software is provided 'as-is', without any express or implied warranty.
13  In no event will the authors be held liable for any damages arising from the use of this software.
14  Permission is granted to anyone to use this software for any purpose,
15  including commercial applications, and to alter it and redistribute it freely,
16  subject to the following restrictions:
17 
18  1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
19  2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
20  3. This notice may not be removed or altered from any source distribution.
21 
22  */
23 
24 #ifndef BT_MULTIBODY_H
25 #define BT_MULTIBODY_H
26 
27 #include "LinearMath/btScalar.h"
28 #include "LinearMath/btVector3.h"
29 #include "LinearMath/btQuaternion.h"
30 #include "LinearMath/btMatrix3x3.h"
31 #include "LinearMath/btAlignedObjectArray.h"
32 
33 ///serialization data, don't change them if you are not familiar with the details of the serialization mechanisms
34 #ifdef BT_USE_DOUBLE_PRECISION
35 #define btMultiBodyData btMultiBodyDoubleData
36 #define btMultiBodyDataName "btMultiBodyDoubleData"
37 #define btMultiBodyLinkData btMultiBodyLinkDoubleData
38 #define btMultiBodyLinkDataName "btMultiBodyLinkDoubleData"
39 #else
40 #define btMultiBodyData btMultiBodyFloatData
41 #define btMultiBodyDataName "btMultiBodyFloatData"
42 #define btMultiBodyLinkData btMultiBodyLinkFloatData
43 #define btMultiBodyLinkDataName "btMultiBodyLinkFloatData"
44 #endif  //BT_USE_DOUBLE_PRECISION
45 
46 #include "btMultiBodyLink.h"
47 class btMultiBodyLinkCollider;
48 
ATTRIBUTE_ALIGNED16(class)49 ATTRIBUTE_ALIGNED16(class)
50 btMultiBody
51 {
52 public:
53 	BT_DECLARE_ALIGNED_ALLOCATOR();
54 
55 	//
56 	// initialization
57 	//
58 
59 	btMultiBody(int n_links,               // NOT including the base
60 				btScalar mass,             // mass of base
61 				const btVector3 &inertia,  // inertia of base, in base frame; assumed diagonal
62 				bool fixedBase,            // whether the base is fixed (true) or can move (false)
63 				bool canSleep, bool deprecatedMultiDof = true);
64 
65 	virtual ~btMultiBody();
66 
67 	//note: fixed link collision with parent is always disabled
68 	void setupFixed(int i, //linkIndex
69 					btScalar mass,
70 					const btVector3 &inertia,
71 					int parent,
72 					const btQuaternion &rotParentToThis,
73 					const btVector3 &parentComToThisPivotOffset,
74 					const btVector3 &thisPivotToThisComOffset, bool deprecatedDisableParentCollision = true);
75 
76 	void setupPrismatic(int i,
77 						btScalar mass,
78 						const btVector3 &inertia,
79 						int parent,
80 						const btQuaternion &rotParentToThis,
81 						const btVector3 &jointAxis,
82 						const btVector3 &parentComToThisPivotOffset,
83 						const btVector3 &thisPivotToThisComOffset,
84 						bool disableParentCollision);
85 
86 	void setupRevolute(int i,  // 0 to num_links-1
87 					   btScalar mass,
88 					   const btVector3 &inertia,
89 					   int parentIndex,
90 					   const btQuaternion &rotParentToThis,          // rotate points in parent frame to this frame, when q = 0
91 					   const btVector3 &jointAxis,                   // in my frame
92 					   const btVector3 &parentComToThisPivotOffset,  // vector from parent COM to joint axis, in PARENT frame
93 					   const btVector3 &thisPivotToThisComOffset,    // vector from joint axis to my COM, in MY frame
94 					   bool disableParentCollision = false);
95 
96 	void setupSpherical(int i,  // linkIndex, 0 to num_links-1
97 						btScalar mass,
98 						const btVector3 &inertia,
99 						int parent,
100 						const btQuaternion &rotParentToThis,          // rotate points in parent frame to this frame, when q = 0
101 						const btVector3 &parentComToThisPivotOffset,  // vector from parent COM to joint axis, in PARENT frame
102 						const btVector3 &thisPivotToThisComOffset,    // vector from joint axis to my COM, in MY frame
103 						bool disableParentCollision = false);
104 
105 	void setupPlanar(int i,  // 0 to num_links-1
106 					 btScalar mass,
107 					 const btVector3 &inertia,
108 					 int parent,
109 					 const btQuaternion &rotParentToThis,  // rotate points in parent frame to this frame, when q = 0
110 					 const btVector3 &rotationAxis,
111 					 const btVector3 &parentComToThisComOffset,  // vector from parent COM to this COM, in PARENT frame
112 					 bool disableParentCollision = false);
113 
114 	const btMultibodyLink &getLink(int index) const
115 	{
116 		return m_links[index];
117 	}
118 
119 	btMultibodyLink &getLink(int index)
120 	{
121 		return m_links[index];
122 	}
123 
124 	void setBaseCollider(btMultiBodyLinkCollider * collider)  //collider can be NULL to disable collision for the base
125 	{
126 		m_baseCollider = collider;
127 	}
128 	const btMultiBodyLinkCollider *getBaseCollider() const
129 	{
130 		return m_baseCollider;
131 	}
132 	btMultiBodyLinkCollider *getBaseCollider()
133 	{
134 		return m_baseCollider;
135 	}
136 
137 	const btMultiBodyLinkCollider *getLinkCollider(int index) const
138 	{
139 		if (index >= 0 && index < getNumLinks())
140 		{
141 			return getLink(index).m_collider;
142 		}
143 		return 0;
144 	}
145 
146 	btMultiBodyLinkCollider *getLinkCollider(int index)
147 	{
148 		if (index >= 0 && index < getNumLinks())
149 		{
150 			return getLink(index).m_collider;
151 		}
152 		return 0;
153 	}
154 
155 	//
156 	// get parent
157 	// input: link num from 0 to num_links-1
158 	// output: link num from 0 to num_links-1, OR -1 to mean the base.
159 	//
160 	int getParent(int link_num) const;
161 
162 	//
163 	// get number of m_links, masses, moments of inertia
164 	//
165 
166 	int getNumLinks() const { return m_links.size(); }
167 	int getNumDofs() const { return m_dofCount; }
168 	int getNumPosVars() const { return m_posVarCnt; }
169 	btScalar getBaseMass() const { return m_baseMass; }
170 	const btVector3 &getBaseInertia() const { return m_baseInertia; }
171 	btScalar getLinkMass(int i) const;
172 	const btVector3 &getLinkInertia(int i) const;
173 
174 	//
175 	// change mass (incomplete: can only change base mass and inertia at present)
176 	//
177 
178 	void setBaseMass(btScalar mass) { m_baseMass = mass; }
179 	void setBaseInertia(const btVector3 &inertia) { m_baseInertia = inertia; }
180 
181 	//
182 	// get/set pos/vel/rot/omega for the base link
183 	//
184 
185 	const btVector3 &getBasePos() const
186 	{
187 		return m_basePos;
188 	}  // in world frame
189 	const btVector3 getBaseVel() const
190 	{
191 		return btVector3(m_realBuf[3], m_realBuf[4], m_realBuf[5]);
192 	}  // in world frame
193 	const btQuaternion &getWorldToBaseRot() const
194 	{
195 		return m_baseQuat;
196 	}
197 
198     const btVector3 &getInterpolateBasePos() const
199     {
200         return m_basePos_interpolate;
201     }  // in world frame
202     const btQuaternion &getInterpolateWorldToBaseRot() const
203     {
204         return m_baseQuat_interpolate;
205     }
206 
207     // rotates world vectors into base frame
208 	btVector3 getBaseOmega() const { return btVector3(m_realBuf[0], m_realBuf[1], m_realBuf[2]); }  // in world frame
209 
210 	void setBasePos(const btVector3 &pos)
211 	{
212 		m_basePos = pos;
213         m_basePos_interpolate = pos;
214 	}
215 
216 	void setBaseWorldTransform(const btTransform &tr)
217 	{
218 		setBasePos(tr.getOrigin());
219 		setWorldToBaseRot(tr.getRotation().inverse());
220 	}
221 
222 	btTransform getBaseWorldTransform() const
223 	{
224 		btTransform tr;
225 		tr.setOrigin(getBasePos());
226 		tr.setRotation(getWorldToBaseRot().inverse());
227 		return tr;
228 	}
229 
230 	void setBaseVel(const btVector3 &vel)
231 	{
232 		m_realBuf[3] = vel[0];
233 		m_realBuf[4] = vel[1];
234 		m_realBuf[5] = vel[2];
235 	}
236 	void setWorldToBaseRot(const btQuaternion &rot)
237 	{
238 		m_baseQuat = rot;  //m_baseQuat asumed to ba alias!?
239         m_baseQuat_interpolate = rot;
240 	}
241 	void setBaseOmega(const btVector3 &omega)
242 	{
243 		m_realBuf[0] = omega[0];
244 		m_realBuf[1] = omega[1];
245 		m_realBuf[2] = omega[2];
246 	}
247 
248 	//
249 	// get/set pos/vel for child m_links (i = 0 to num_links-1)
250 	//
251 
252 	btScalar getJointPos(int i) const;
253 	btScalar getJointVel(int i) const;
254 
255 	btScalar *getJointVelMultiDof(int i);
256 	btScalar *getJointPosMultiDof(int i);
257 
258 	const btScalar *getJointVelMultiDof(int i) const;
259 	const btScalar *getJointPosMultiDof(int i) const;
260 
261 	void setJointPos(int i, btScalar q);
262 	void setJointVel(int i, btScalar qdot);
263 	void setJointPosMultiDof(int i, const double *q);
264 	void setJointVelMultiDof(int i, const double *qdot);
265 	void setJointPosMultiDof(int i, const float *q);
266 	void setJointVelMultiDof(int i, const float *qdot);
267 
268 	//
269 	// direct access to velocities as a vector of 6 + num_links elements.
270 	// (omega first, then v, then joint velocities.)
271 	//
272 	const btScalar *getVelocityVector() const
273 	{
274 		return &m_realBuf[0];
275 	}
276 
277     const btScalar *getDeltaVelocityVector() const
278     {
279         return &m_deltaV[0];
280     }
281 	/*    btScalar * getVelocityVector()
282 	{
283 		return &real_buf[0];
284 	}
285   */
286 
287 	//
288 	// get the frames of reference (positions and orientations) of the child m_links
289 	// (i = 0 to num_links-1)
290 	//
291 
292 	const btVector3 &getRVector(int i) const;              // vector from COM(parent(i)) to COM(i), in frame i's coords
293 	const btQuaternion &getParentToLocalRot(int i) const;  // rotates vectors in frame parent(i) to vectors in frame i.
294     const btVector3 &getInterpolateRVector(int i) const;              // vector from COM(parent(i)) to COM(i), in frame i's coords
295     const btQuaternion &getInterpolateParentToLocalRot(int i) const;  // rotates vectors in frame parent(i) to vectors in frame i.
296 
297 	//
298 	// transform vectors in local frame of link i to world frame (or vice versa)
299 	//
300 	btVector3 localPosToWorld(int i, const btVector3 &local_pos) const;
301 	btVector3 localDirToWorld(int i, const btVector3 &local_dir) const;
302 	btVector3 worldPosToLocal(int i, const btVector3 &world_pos) const;
303 	btVector3 worldDirToLocal(int i, const btVector3 &world_dir) const;
304 
305 	//
306 	// transform a frame in local coordinate to a frame in world coordinate
307 	//
308 	btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &local_frame) const;
309 
310 	//
311 	// calculate kinetic energy and angular momentum
312 	// useful for debugging.
313 	//
314 
315 	btScalar getKineticEnergy() const;
316 	btVector3 getAngularMomentum() const;
317 
318 	//
319 	// set external forces and torques. Note all external forces/torques are given in the WORLD frame.
320 	//
321 
322 	void clearForcesAndTorques();
323 	void clearConstraintForces();
324 
325 	void clearVelocities();
326 
327 	void addBaseForce(const btVector3 &f)
328 	{
329 		m_baseForce += f;
330 	}
331 	void addBaseTorque(const btVector3 &t) { m_baseTorque += t; }
332 	void addLinkForce(int i, const btVector3 &f);
333 	void addLinkTorque(int i, const btVector3 &t);
334 
335 	void addBaseConstraintForce(const btVector3 &f)
336 	{
337 		m_baseConstraintForce += f;
338 	}
339 	void addBaseConstraintTorque(const btVector3 &t) { m_baseConstraintTorque += t; }
340 	void addLinkConstraintForce(int i, const btVector3 &f);
341 	void addLinkConstraintTorque(int i, const btVector3 &t);
342 
343 	void addJointTorque(int i, btScalar Q);
344 	void addJointTorqueMultiDof(int i, int dof, btScalar Q);
345 	void addJointTorqueMultiDof(int i, const btScalar *Q);
346 
347 	const btVector3 &getBaseForce() const { return m_baseForce; }
348 	const btVector3 &getBaseTorque() const { return m_baseTorque; }
349 	const btVector3 &getLinkForce(int i) const;
350 	const btVector3 &getLinkTorque(int i) const;
351 	btScalar getJointTorque(int i) const;
352 	btScalar *getJointTorqueMultiDof(int i);
353 
354 	//
355 	// dynamics routines.
356 	//
357 
358 	// timestep the velocities (given the external forces/torques set using addBaseForce etc).
359 	// also sets up caches for calcAccelerationDeltas.
360 	//
361 	// Note: the caller must provide three vectors which are used as
362 	// temporary scratch space. The idea here is to reduce dynamic
363 	// memory allocation: the same scratch vectors can be re-used
364 	// again and again for different Multibodies, instead of each
365 	// btMultiBody allocating (and then deallocating) their own
366 	// individual scratch buffers. This gives a considerable speed
367 	// improvement, at least on Windows (where dynamic memory
368 	// allocation appears to be fairly slow).
369 	//
370 
371 	void computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar dt,
372 															  btAlignedObjectArray<btScalar> & scratch_r,
373 															  btAlignedObjectArray<btVector3> & scratch_v,
374 															  btAlignedObjectArray<btMatrix3x3> & scratch_m,
375 															  bool isConstraintPass,
376                                                               bool jointFeedbackInWorldSpace,
377                                                               bool jointFeedbackInJointFrame
378                                                               );
379 
380 	///stepVelocitiesMultiDof is deprecated, use computeAccelerationsArticulatedBodyAlgorithmMultiDof instead
381 	//void stepVelocitiesMultiDof(btScalar dt,
382 	//							btAlignedObjectArray<btScalar> & scratch_r,
383 	//							btAlignedObjectArray<btVector3> & scratch_v,
384 	//							btAlignedObjectArray<btMatrix3x3> & scratch_m,
385 	//							bool isConstraintPass = false)
386 	//{
387 	//	computeAccelerationsArticulatedBodyAlgorithmMultiDof(dt, scratch_r, scratch_v, scratch_m, isConstraintPass, false, false);
388 	//}
389 
390 	// calcAccelerationDeltasMultiDof
391 	// input: force vector (in same format as jacobian, i.e.:
392 	//                      3 torque values, 3 force values, num_links joint torque values)
393 	// output: 3 omegadot values, 3 vdot values, num_links q_double_dot values
394 	// (existing contents of output array are replaced)
395 	// calcAccelerationDeltasMultiDof must have been called first.
396 	void calcAccelerationDeltasMultiDof(const btScalar *force, btScalar *output,
397 										btAlignedObjectArray<btScalar> &scratch_r,
398 										btAlignedObjectArray<btVector3> &scratch_v) const;
399 
400 	void applyDeltaVeeMultiDof2(const btScalar *delta_vee, btScalar multiplier)
401 	{
402 		for (int dof = 0; dof < 6 + getNumDofs(); ++dof)
403 		{
404 			m_deltaV[dof] += delta_vee[dof] * multiplier;
405 		}
406 	}
407 	void processDeltaVeeMultiDof2()
408 	{
409 		applyDeltaVeeMultiDof(&m_deltaV[0], 1);
410 
411 		for (int dof = 0; dof < 6 + getNumDofs(); ++dof)
412 		{
413 			m_deltaV[dof] = 0.f;
414 		}
415 	}
416 
417 	void applyDeltaVeeMultiDof(const btScalar *delta_vee, btScalar multiplier)
418 	{
419 		//for (int dof = 0; dof < 6 + getNumDofs(); ++dof)
420 		//	printf("%.4f ", delta_vee[dof]*multiplier);
421 		//printf("\n");
422 
423 		//btScalar sum = 0;
424 		//for (int dof = 0; dof < 6 + getNumDofs(); ++dof)
425 		//{
426 		//	sum += delta_vee[dof]*multiplier*delta_vee[dof]*multiplier;
427 		//}
428 		//btScalar l = btSqrt(sum);
429 
430 		//if (l>m_maxAppliedImpulse)
431 		//{
432 		//	multiplier *= m_maxAppliedImpulse/l;
433 		//}
434 
435 		for (int dof = 0; dof < 6 + getNumDofs(); ++dof)
436 		{
437 			m_realBuf[dof] += delta_vee[dof] * multiplier;
438 			btClamp(m_realBuf[dof], -m_maxCoordinateVelocity, m_maxCoordinateVelocity);
439 		}
440 	}
441 
442 	// timestep the positions (given current velocities).
443 	void stepPositionsMultiDof(btScalar dt, btScalar *pq = 0, btScalar *pqd = 0);
444 
445     // predict the positions
446     void predictPositionsMultiDof(btScalar dt);
447 
448 	//
449 	// contacts
450 	//
451 
452 	// This routine fills out a contact constraint jacobian for this body.
453 	// the 'normal' supplied must be -n for body1 or +n for body2 of the contact.
454 	// 'normal' & 'contact_point' are both given in world coordinates.
455 
456 	void fillContactJacobianMultiDof(int link,
457 									 const btVector3 &contact_point,
458 									 const btVector3 &normal,
459 									 btScalar *jac,
460 									 btAlignedObjectArray<btScalar> &scratch_r,
461 									 btAlignedObjectArray<btVector3> &scratch_v,
462 									 btAlignedObjectArray<btMatrix3x3> &scratch_m) const { fillConstraintJacobianMultiDof(link, contact_point, btVector3(0, 0, 0), normal, jac, scratch_r, scratch_v, scratch_m); }
463 
464 	//a more general version of fillContactJacobianMultiDof which does not assume..
465 	//.. that the constraint in question is contact or, to be more precise, constrains linear velocity only
466 	void fillConstraintJacobianMultiDof(int link,
467 										const btVector3 &contact_point,
468 										const btVector3 &normal_ang,
469 										const btVector3 &normal_lin,
470 										btScalar *jac,
471 										btAlignedObjectArray<btScalar> &scratch_r,
472 										btAlignedObjectArray<btVector3> &scratch_v,
473 										btAlignedObjectArray<btMatrix3x3> &scratch_m) const;
474 
475 	//
476 	// sleeping
477 	//
478 	void setCanSleep(bool canSleep)
479 	{
480 		if (m_canWakeup)
481 		{
482 			m_canSleep = canSleep;
483 		}
484 	}
485 
486 	bool getCanSleep() const
487 	{
488 		return m_canSleep;
489 	}
490 
491 	bool getCanWakeup() const
492 	{
493 		return m_canWakeup;
494 	}
495 
496 	void setCanWakeup(bool canWakeup)
497 	{
498 		m_canWakeup = canWakeup;
499 	}
500 	bool isAwake() const { return m_awake; }
501 	void wakeUp();
502 	void goToSleep();
503 	void checkMotionAndSleepIfRequired(btScalar timestep);
504 
505 	bool hasFixedBase() const
506 	{
507 		return m_fixedBase;
508 	}
509 
510 	void setFixedBase(bool fixedBase)
511 	{
512 		m_fixedBase = fixedBase;
513 	}
514 
515 	int getCompanionId() const
516 	{
517 		return m_companionId;
518 	}
519 	void setCompanionId(int id)
520 	{
521 		//printf("for %p setCompanionId(%d)\n",this, id);
522 		m_companionId = id;
523 	}
524 
525 	void setNumLinks(int numLinks)  //careful: when changing the number of m_links, make sure to re-initialize or update existing m_links
526 	{
527 		m_links.resize(numLinks);
528 	}
529 
530 	btScalar getLinearDamping() const
531 	{
532 		return m_linearDamping;
533 	}
534 	void setLinearDamping(btScalar damp)
535 	{
536 		m_linearDamping = damp;
537 	}
538 	btScalar getAngularDamping() const
539 	{
540 		return m_angularDamping;
541 	}
542 	void setAngularDamping(btScalar damp)
543 	{
544 		m_angularDamping = damp;
545 	}
546 
547 	bool getUseGyroTerm() const
548 	{
549 		return m_useGyroTerm;
550 	}
551 	void setUseGyroTerm(bool useGyro)
552 	{
553 		m_useGyroTerm = useGyro;
554 	}
555 	btScalar getMaxCoordinateVelocity() const
556 	{
557 		return m_maxCoordinateVelocity;
558 	}
559 	void setMaxCoordinateVelocity(btScalar maxVel)
560 	{
561 		m_maxCoordinateVelocity = maxVel;
562 	}
563 
564 	btScalar getMaxAppliedImpulse() const
565 	{
566 		return m_maxAppliedImpulse;
567 	}
568 	void setMaxAppliedImpulse(btScalar maxImp)
569 	{
570 		m_maxAppliedImpulse = maxImp;
571 	}
572 	void setHasSelfCollision(bool hasSelfCollision)
573 	{
574 		m_hasSelfCollision = hasSelfCollision;
575 	}
576 	bool hasSelfCollision() const
577 	{
578 		return m_hasSelfCollision;
579 	}
580 
581 	void finalizeMultiDof();
582 
583 	void useRK4Integration(bool use) { m_useRK4 = use; }
584 	bool isUsingRK4Integration() const { return m_useRK4; }
585 	void useGlobalVelocities(bool use) { m_useGlobalVelocities = use; }
586 	bool isUsingGlobalVelocities() const { return m_useGlobalVelocities; }
587 
588 	bool isPosUpdated() const
589 	{
590 		return __posUpdated;
591 	}
592 	void setPosUpdated(bool updated)
593 	{
594 		__posUpdated = updated;
595 	}
596 
597 	//internalNeedsJointFeedback is for internal use only
598 	bool internalNeedsJointFeedback() const
599 	{
600 		return m_internalNeedsJointFeedback;
601 	}
602 	void forwardKinematics(btAlignedObjectArray<btQuaternion>& world_to_local, btAlignedObjectArray<btVector3> & local_origin);
603 
604 	void compTreeLinkVelocities(btVector3 * omega, btVector3 * vel) const;
605 
606 	void updateCollisionObjectWorldTransforms(btAlignedObjectArray<btQuaternion> & world_to_local, btAlignedObjectArray<btVector3> & local_origin);
607     void updateCollisionObjectInterpolationWorldTransforms(btAlignedObjectArray<btQuaternion> & world_to_local, btAlignedObjectArray<btVector3> & local_origin);
608 
609 	virtual int calculateSerializeBufferSize() const;
610 
611 	///fills the dataBuffer and returns the struct name (and 0 on failure)
612 	virtual const char *serialize(void *dataBuffer, class btSerializer *serializer) const;
613 
614 	const char *getBaseName() const
615 	{
616 		return m_baseName;
617 	}
618 	///memory of setBaseName needs to be manager by user
619 	void setBaseName(const char *name)
620 	{
621 		m_baseName = name;
622 	}
623 
624 	///users can point to their objects, userPointer is not used by Bullet
625 	void *getUserPointer() const
626 	{
627 		return m_userObjectPointer;
628 	}
629 
630 	int getUserIndex() const
631 	{
632 		return m_userIndex;
633 	}
634 
635 	int getUserIndex2() const
636 	{
637 		return m_userIndex2;
638 	}
639 	///users can point to their objects, userPointer is not used by Bullet
640 	void setUserPointer(void *userPointer)
641 	{
642 		m_userObjectPointer = userPointer;
643 	}
644 
645 	///users can point to their objects, userPointer is not used by Bullet
646 	void setUserIndex(int index)
647 	{
648 		m_userIndex = index;
649 	}
650 
651 	void setUserIndex2(int index)
652 	{
653 		m_userIndex2 = index;
654 	}
655 
656 	static void spatialTransform(const btMatrix3x3 &rotation_matrix,  // rotates vectors in 'from' frame to vectors in 'to' frame
657 		const btVector3 &displacement,     // vector from origin of 'from' frame to origin of 'to' frame, in 'to' coordinates
658 		const btVector3 &top_in,       // top part of input vector
659 		const btVector3 &bottom_in,    // bottom part of input vector
660 		btVector3 &top_out,         // top part of output vector
661 		btVector3 &bottom_out);      // bottom part of output vector
662 
663 
664 
665 private:
666 	btMultiBody(const btMultiBody &);     // not implemented
667 	void operator=(const btMultiBody &);  // not implemented
668 
669 	void solveImatrix(const btVector3 &rhs_top, const btVector3 &rhs_bot, btScalar result[6]) const;
670 	void solveImatrix(const btSpatialForceVector &rhs, btSpatialMotionVector &result) const;
671 
672 	void updateLinksDofOffsets()
673 	{
674 		int dofOffset = 0, cfgOffset = 0;
675 		for (int bidx = 0; bidx < m_links.size(); ++bidx)
676 		{
677 			m_links[bidx].m_dofOffset = dofOffset;
678 			m_links[bidx].m_cfgOffset = cfgOffset;
679 			dofOffset += m_links[bidx].m_dofCount;
680 			cfgOffset += m_links[bidx].m_posVarCount;
681 		}
682 	}
683 
684 	void mulMatrix(btScalar * pA, btScalar * pB, int rowsA, int colsA, int rowsB, int colsB, btScalar *pC) const;
685 
686 private:
687 	btMultiBodyLinkCollider *m_baseCollider;  //can be NULL
688 	const char *m_baseName;                   //memory needs to be manager by user!
689 
690 	btVector3 m_basePos;      // position of COM of base (world frame)
691     btVector3 m_basePos_interpolate;      // position of interpolated COM of base (world frame)
692 	btQuaternion m_baseQuat;  // rotates world points into base frame
693     btQuaternion m_baseQuat_interpolate;
694 
695 	btScalar m_baseMass;      // mass of the base
696 	btVector3 m_baseInertia;  // inertia of the base (in local frame; diagonal)
697 
698 	btVector3 m_baseForce;   // external force applied to base. World frame.
699 	btVector3 m_baseTorque;  // external torque applied to base. World frame.
700 
701 	btVector3 m_baseConstraintForce;   // external force applied to base. World frame.
702 	btVector3 m_baseConstraintTorque;  // external torque applied to base. World frame.
703 
704 	btAlignedObjectArray<btMultibodyLink> m_links;  // array of m_links, excluding the base. index from 0 to num_links-1.
705 
706 	//
707 	// realBuf:
708 	//  offset         size            array
709 	//   0              6 + num_links   v (base_omega; base_vel; joint_vels)					MULTIDOF [sysdof x sysdof for D matrices (TOO MUCH!) + pos_delta which is sys-cfg sized]
710 	//   6+num_links    num_links       D
711 	//
712 	// vectorBuf:
713 	//  offset         size         array
714 	//   0              num_links    h_top
715 	//   num_links      num_links    h_bottom
716 	//
717 	// matrixBuf:
718 	//  offset         size         array
719 	//   0              num_links+1  rot_from_parent
720 	//
721 	btAlignedObjectArray<btScalar> m_deltaV;
722 	btAlignedObjectArray<btScalar> m_realBuf;
723 	btAlignedObjectArray<btVector3> m_vectorBuf;
724 	btAlignedObjectArray<btMatrix3x3> m_matrixBuf;
725 
726 	btMatrix3x3 m_cachedInertiaTopLeft;
727 	btMatrix3x3 m_cachedInertiaTopRight;
728 	btMatrix3x3 m_cachedInertiaLowerLeft;
729 	btMatrix3x3 m_cachedInertiaLowerRight;
730 	bool m_cachedInertiaValid;
731 
732 	bool m_fixedBase;
733 
734 	// Sleep parameters.
735 	bool m_awake;
736 	bool m_canSleep;
737 	bool m_canWakeup;
738 	btScalar m_sleepTimer;
739 
740 	void *m_userObjectPointer;
741 	int m_userIndex2;
742 	int m_userIndex;
743 
744 	int m_companionId;
745 	btScalar m_linearDamping;
746 	btScalar m_angularDamping;
747 	bool m_useGyroTerm;
748 	btScalar m_maxAppliedImpulse;
749 	btScalar m_maxCoordinateVelocity;
750 	bool m_hasSelfCollision;
751 
752 	bool __posUpdated;
753 	int m_dofCount, m_posVarCnt;
754 
755 	bool m_useRK4, m_useGlobalVelocities;
756 	//for global velocities, see 8.3.2B Proposed resolution in Jakub Stepien PhD Thesis
757 	//https://drive.google.com/file/d/0Bz3vEa19XOYGNWdZWGpMdUdqVmZ5ZVBOaEh4ZnpNaUxxZFNV/view?usp=sharing
758 
759 	///the m_needsJointFeedback gets updated/computed during the stepVelocitiesMultiDof and it for internal usage only
760 	bool m_internalNeedsJointFeedback;
761 };
762 
763 struct btMultiBodyLinkDoubleData
764 {
765 	btQuaternionDoubleData m_zeroRotParentToThis;
766 	btVector3DoubleData m_parentComToThisPivotOffset;
767 	btVector3DoubleData m_thisPivotToThisComOffset;
768 	btVector3DoubleData m_jointAxisTop[6];
769 	btVector3DoubleData m_jointAxisBottom[6];
770 
771 	btVector3DoubleData m_linkInertia;  // inertia of the base (in local frame; diagonal)
772 	btVector3DoubleData m_absFrameTotVelocityTop;
773 	btVector3DoubleData m_absFrameTotVelocityBottom;
774 	btVector3DoubleData m_absFrameLocVelocityTop;
775 	btVector3DoubleData m_absFrameLocVelocityBottom;
776 
777 	double m_linkMass;
778 	int m_parentIndex;
779 	int m_jointType;
780 
781 	int m_dofCount;
782 	int m_posVarCount;
783 	double m_jointPos[7];
784 	double m_jointVel[6];
785 	double m_jointTorque[6];
786 
787 	double m_jointDamping;
788 	double m_jointFriction;
789 	double m_jointLowerLimit;
790 	double m_jointUpperLimit;
791 	double m_jointMaxForce;
792 	double m_jointMaxVelocity;
793 
794 	char *m_linkName;
795 	char *m_jointName;
796 	btCollisionObjectDoubleData *m_linkCollider;
797 	char *m_paddingPtr;
798 };
799 
800 struct btMultiBodyLinkFloatData
801 {
802 	btQuaternionFloatData m_zeroRotParentToThis;
803 	btVector3FloatData m_parentComToThisPivotOffset;
804 	btVector3FloatData m_thisPivotToThisComOffset;
805 	btVector3FloatData m_jointAxisTop[6];
806 	btVector3FloatData m_jointAxisBottom[6];
807 	btVector3FloatData m_linkInertia;  // inertia of the base (in local frame; diagonal)
808 	btVector3FloatData m_absFrameTotVelocityTop;
809 	btVector3FloatData m_absFrameTotVelocityBottom;
810 	btVector3FloatData m_absFrameLocVelocityTop;
811 	btVector3FloatData m_absFrameLocVelocityBottom;
812 
813 	int m_dofCount;
814 	float m_linkMass;
815 	int m_parentIndex;
816 	int m_jointType;
817 
818 	float m_jointPos[7];
819 	float m_jointVel[6];
820 	float m_jointTorque[6];
821 	int m_posVarCount;
822 	float m_jointDamping;
823 	float m_jointFriction;
824 	float m_jointLowerLimit;
825 	float m_jointUpperLimit;
826 	float m_jointMaxForce;
827 	float m_jointMaxVelocity;
828 
829 	char *m_linkName;
830 	char *m_jointName;
831 	btCollisionObjectFloatData *m_linkCollider;
832 	char *m_paddingPtr;
833 };
834 
835 ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
836 struct btMultiBodyDoubleData
837 {
838 	btVector3DoubleData m_baseWorldPosition;
839 	btQuaternionDoubleData m_baseWorldOrientation;
840 	btVector3DoubleData m_baseLinearVelocity;
841 	btVector3DoubleData m_baseAngularVelocity;
842 	btVector3DoubleData m_baseInertia;  // inertia of the base (in local frame; diagonal)
843 	double m_baseMass;
844 	int m_numLinks;
845 	char m_padding[4];
846 
847 	char *m_baseName;
848 	btMultiBodyLinkDoubleData *m_links;
849 	btCollisionObjectDoubleData *m_baseCollider;
850 };
851 
852 ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
853 struct btMultiBodyFloatData
854 {
855 	btVector3FloatData m_baseWorldPosition;
856 	btQuaternionFloatData m_baseWorldOrientation;
857 	btVector3FloatData m_baseLinearVelocity;
858 	btVector3FloatData m_baseAngularVelocity;
859 
860 	btVector3FloatData m_baseInertia;  // inertia of the base (in local frame; diagonal)
861 	float m_baseMass;
862 	int m_numLinks;
863 
864 	char *m_baseName;
865 	btMultiBodyLinkFloatData *m_links;
866 	btCollisionObjectFloatData *m_baseCollider;
867 };
868 
869 #endif
870