Bullet Collision Detection & Physics Library
btMultiBody.cpp
Go to the documentation of this file.
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: replacing Eigen math library by Bullet LinearMath and a dedicated 6x6 matrix inverse (solveImatrix)
10 
11  This software is provided 'as-is', without any express or implied warranty.
12  In no event will the authors be held liable for any damages arising from the use of this software.
13  Permission is granted to anyone to use this software for any purpose,
14  including commercial applications, and to alter it and redistribute it freely,
15  subject to the following restrictions:
16 
17  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.
18  2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
19  3. This notice may not be removed or altered from any source distribution.
20 
21  */
22 
23 
24 #include "btMultiBody.h"
25 #include "btMultiBodyLink.h"
27 
28 // #define INCLUDE_GYRO_TERM
29 
30 namespace {
31  const btScalar SLEEP_EPSILON = btScalar(0.05); // this is a squared velocity (m^2 s^-2)
32  const btScalar SLEEP_TIMEOUT = btScalar(2); // in seconds
33 }
34 
35 
36 
37 
38 //
39 // Various spatial helper functions
40 //
41 
42 namespace {
43  void SpatialTransform(const btMatrix3x3 &rotation_matrix, // rotates vectors in 'from' frame to vectors in 'to' frame
44  const btVector3 &displacement, // vector from origin of 'from' frame to origin of 'to' frame, in 'to' coordinates
45  const btVector3 &top_in, // top part of input vector
46  const btVector3 &bottom_in, // bottom part of input vector
47  btVector3 &top_out, // top part of output vector
48  btVector3 &bottom_out) // bottom part of output vector
49  {
50  top_out = rotation_matrix * top_in;
51  bottom_out = -displacement.cross(top_out) + rotation_matrix * bottom_in;
52  }
53 
54  void InverseSpatialTransform(const btMatrix3x3 &rotation_matrix,
55  const btVector3 &displacement,
56  const btVector3 &top_in,
57  const btVector3 &bottom_in,
58  btVector3 &top_out,
59  btVector3 &bottom_out)
60  {
61  top_out = rotation_matrix.transpose() * top_in;
62  bottom_out = rotation_matrix.transpose() * (bottom_in + displacement.cross(top_in));
63  }
64 
65  btScalar SpatialDotProduct(const btVector3 &a_top,
66  const btVector3 &a_bottom,
67  const btVector3 &b_top,
68  const btVector3 &b_bottom)
69  {
70  return a_bottom.dot(b_top) + a_top.dot(b_bottom);
71  }
72 }
73 
74 
75 //
76 // Implementation of class btMultiBody
77 //
78 
80  btScalar mass,
81  const btVector3 &inertia,
82  bool fixed_base_,
83  bool can_sleep_)
84  : base_quat(0, 0, 0, 1),
85  base_mass(mass),
86  base_inertia(inertia),
87 
88  fixed_base(fixed_base_),
89  awake(true),
90  can_sleep(can_sleep_),
91  sleep_timer(0),
92  m_baseCollider(0),
93  m_linearDamping(0.04f),
94  m_angularDamping(0.04f),
95  m_useGyroTerm(true),
96  m_maxAppliedImpulse(1000.f),
97  m_hasSelfCollision(true)
98 {
99  links.resize(n_links);
100 
101  vector_buf.resize(2*n_links);
102  matrix_buf.resize(n_links + 1);
103  m_real_buf.resize(6 + 2*n_links);
104  base_pos.setValue(0, 0, 0);
105  base_force.setValue(0, 0, 0);
106  base_torque.setValue(0, 0, 0);
107 }
108 
110 {
111 }
112 
114  btScalar mass,
115  const btVector3 &inertia,
116  int parent,
117  const btQuaternion &rot_parent_to_this,
118  const btVector3 &joint_axis,
119  const btVector3 &r_vector_when_q_zero,
120  bool disableParentCollision)
121 {
122  links[i].mass = mass;
123  links[i].inertia = inertia;
124  links[i].parent = parent;
125  links[i].zero_rot_parent_to_this = rot_parent_to_this;
126  links[i].axis_top.setValue(0,0,0);
127  links[i].axis_bottom = joint_axis;
128  links[i].e_vector = r_vector_when_q_zero;
129  links[i].is_revolute = false;
130  links[i].cached_rot_parent_to_this = rot_parent_to_this;
131  if (disableParentCollision)
133 
134  links[i].updateCache();
135 }
136 
138  btScalar mass,
139  const btVector3 &inertia,
140  int parent,
141  const btQuaternion &zero_rot_parent_to_this,
142  const btVector3 &joint_axis,
143  const btVector3 &parent_axis_position,
144  const btVector3 &my_axis_position,
145  bool disableParentCollision)
146 {
147  links[i].mass = mass;
148  links[i].inertia = inertia;
149  links[i].parent = parent;
150  links[i].zero_rot_parent_to_this = zero_rot_parent_to_this;
151  links[i].axis_top = joint_axis;
152  links[i].axis_bottom = joint_axis.cross(my_axis_position);
153  links[i].d_vector = my_axis_position;
154  links[i].e_vector = parent_axis_position;
155  links[i].is_revolute = true;
156  if (disableParentCollision)
158  links[i].updateCache();
159 }
160 
161 
162 
163 
164 
165 int btMultiBody::getParent(int i) const
166 {
167  return links[i].parent;
168 }
169 
171 {
172  return links[i].mass;
173 }
174 
176 {
177  return links[i].inertia;
178 }
179 
181 {
182  return links[i].joint_pos;
183 }
184 
186 {
187  return m_real_buf[6 + i];
188 }
189 
191 {
192  links[i].joint_pos = q;
193  links[i].updateCache();
194 }
195 
197 {
198  m_real_buf[6 + i] = qdot;
199 }
200 
201 const btVector3 & btMultiBody::getRVector(int i) const
202 {
203  return links[i].cached_r_vector;
204 }
205 
207 {
208  return links[i].cached_rot_parent_to_this;
209 }
210 
211 btVector3 btMultiBody::localPosToWorld(int i, const btVector3 &local_pos) const
212 {
213  btVector3 result = local_pos;
214  while (i != -1) {
215  // 'result' is in frame i. transform it to frame parent(i)
216  result += getRVector(i);
217  result = quatRotate(getParentToLocalRot(i).inverse(),result);
218  i = getParent(i);
219  }
220 
221  // 'result' is now in the base frame. transform it to world frame
222  result = quatRotate(getWorldToBaseRot().inverse() ,result);
223  result += getBasePos();
224 
225  return result;
226 }
227 
228 btVector3 btMultiBody::worldPosToLocal(int i, const btVector3 &world_pos) const
229 {
230  if (i == -1) {
231  // world to base
232  return quatRotate(getWorldToBaseRot(),(world_pos - getBasePos()));
233  } else {
234  // find position in parent frame, then transform to current frame
235  return quatRotate(getParentToLocalRot(i),worldPosToLocal(getParent(i), world_pos)) - getRVector(i);
236  }
237 }
238 
239 btVector3 btMultiBody::localDirToWorld(int i, const btVector3 &local_dir) const
240 {
241  btVector3 result = local_dir;
242  while (i != -1) {
243  result = quatRotate(getParentToLocalRot(i).inverse() , result);
244  i = getParent(i);
245  }
246  result = quatRotate(getWorldToBaseRot().inverse() , result);
247  return result;
248 }
249 
250 btVector3 btMultiBody::worldDirToLocal(int i, const btVector3 &world_dir) const
251 {
252  if (i == -1) {
253  return quatRotate(getWorldToBaseRot(), world_dir);
254  } else {
255  return quatRotate(getParentToLocalRot(i) ,worldDirToLocal(getParent(i), world_dir));
256  }
257 }
258 
260 {
261  int num_links = getNumLinks();
262  // Calculates the velocities of each link (and the base) in its local frame
263  omega[0] = quatRotate(base_quat ,getBaseOmega());
264  vel[0] = quatRotate(base_quat ,getBaseVel());
265 
266  for (int i = 0; i < num_links; ++i) {
267  const int parent = links[i].parent;
268 
269  // transform parent vel into this frame, store in omega[i+1], vel[i+1]
270  SpatialTransform(btMatrix3x3(links[i].cached_rot_parent_to_this), links[i].cached_r_vector,
271  omega[parent+1], vel[parent+1],
272  omega[i+1], vel[i+1]);
273 
274  // now add qidot * shat_i
275  omega[i+1] += getJointVel(i) * links[i].axis_top;
276  vel[i+1] += getJointVel(i) * links[i].axis_bottom;
277  }
278 }
279 
281 {
282  int num_links = getNumLinks();
283  // TODO: would be better not to allocate memory here
284  btAlignedObjectArray<btVector3> omega;omega.resize(num_links+1);
285  btAlignedObjectArray<btVector3> vel;vel.resize(num_links+1);
286  compTreeLinkVelocities(&omega[0], &vel[0]);
287 
288  // we will do the factor of 0.5 at the end
289  btScalar result = base_mass * vel[0].dot(vel[0]);
290  result += omega[0].dot(base_inertia * omega[0]);
291 
292  for (int i = 0; i < num_links; ++i) {
293  result += links[i].mass * vel[i+1].dot(vel[i+1]);
294  result += omega[i+1].dot(links[i].inertia * omega[i+1]);
295  }
296 
297  return 0.5f * result;
298 }
299 
301 {
302  int num_links = getNumLinks();
303  // TODO: would be better not to allocate memory here
304  btAlignedObjectArray<btVector3> omega;omega.resize(num_links+1);
305  btAlignedObjectArray<btVector3> vel;vel.resize(num_links+1);
306  btAlignedObjectArray<btQuaternion> rot_from_world;rot_from_world.resize(num_links+1);
307  compTreeLinkVelocities(&omega[0], &vel[0]);
308 
309  rot_from_world[0] = base_quat;
310  btVector3 result = quatRotate(rot_from_world[0].inverse() , (base_inertia * omega[0]));
311 
312  for (int i = 0; i < num_links; ++i) {
313  rot_from_world[i+1] = links[i].cached_rot_parent_to_this * rot_from_world[links[i].parent+1];
314  result += (quatRotate(rot_from_world[i+1].inverse() , (links[i].inertia * omega[i+1])));
315  }
316 
317  return result;
318 }
319 
320 
322 {
323  base_force.setValue(0, 0, 0);
324  base_torque.setValue(0, 0, 0);
325 
326  for (int i = 0; i < getNumLinks(); ++i) {
327  links[i].applied_force.setValue(0, 0, 0);
328  links[i].applied_torque.setValue(0, 0, 0);
329  links[i].joint_torque = 0;
330  }
331 }
332 
334 {
335  for (int i = 0; i < 6 + getNumLinks(); ++i)
336  {
337  m_real_buf[i] = 0.f;
338  }
339 }
341 {
342  links[i].applied_force += f;
343 }
344 
346 {
347  links[i].applied_torque += t;
348 }
349 
351 {
352  links[i].joint_torque += Q;
353 }
354 
356 {
357  return links[i].applied_force;
358 }
359 
361 {
362  return links[i].applied_torque;
363 }
364 
366 {
367  return links[i].joint_torque;
368 }
369 
370 
371 inline btMatrix3x3 vecMulVecTranspose(const btVector3& v0, const btVector3& v1Transposed)
372 {
373  btVector3 row0 = btVector3(
374  v0.x() * v1Transposed.x(),
375  v0.x() * v1Transposed.y(),
376  v0.x() * v1Transposed.z());
377  btVector3 row1 = btVector3(
378  v0.y() * v1Transposed.x(),
379  v0.y() * v1Transposed.y(),
380  v0.y() * v1Transposed.z());
381  btVector3 row2 = btVector3(
382  v0.z() * v1Transposed.x(),
383  v0.z() * v1Transposed.y(),
384  v0.z() * v1Transposed.z());
385 
386  btMatrix3x3 m(row0[0],row0[1],row0[2],
387  row1[0],row1[1],row1[2],
388  row2[0],row2[1],row2[2]);
389  return m;
390 }
391 
392 
397 {
398  // Implement Featherstone's algorithm to calculate joint accelerations (q_double_dot)
399  // and the base linear & angular accelerations.
400 
401  // We apply damping forces in this routine as well as any external forces specified by the
402  // caller (via addBaseForce etc).
403 
404  // output should point to an array of 6 + num_links reals.
405  // Format is: 3 angular accelerations (in world frame), 3 linear accelerations (in world frame),
406  // num_links joint acceleration values.
407 
408  int num_links = getNumLinks();
409 
410  const btScalar DAMPING_K1_LINEAR = m_linearDamping;
411  const btScalar DAMPING_K2_LINEAR = m_linearDamping;
412 
413  const btScalar DAMPING_K1_ANGULAR = m_angularDamping;
414  const btScalar DAMPING_K2_ANGULAR= m_angularDamping;
415 
416  btVector3 base_vel = getBaseVel();
417  btVector3 base_omega = getBaseOmega();
418 
419  // Temporary matrices/vectors -- use scratch space from caller
420  // so that we don't have to keep reallocating every frame
421 
422  scratch_r.resize(2*num_links + 6);
423  scratch_v.resize(8*num_links + 6);
424  scratch_m.resize(4*num_links + 4);
425 
426  btScalar * r_ptr = &scratch_r[0];
427  btScalar * output = &scratch_r[num_links]; // "output" holds the q_double_dot results
428  btVector3 * v_ptr = &scratch_v[0];
429 
430  // vhat_i (top = angular, bottom = linear part)
431  btVector3 * vel_top_angular = v_ptr; v_ptr += num_links + 1;
432  btVector3 * vel_bottom_linear = v_ptr; v_ptr += num_links + 1;
433 
434  // zhat_i^A
435  btVector3 * zero_acc_top_angular = v_ptr; v_ptr += num_links + 1;
436  btVector3 * zero_acc_bottom_linear = v_ptr; v_ptr += num_links + 1;
437 
438  // chat_i (note NOT defined for the base)
439  btVector3 * coriolis_top_angular = v_ptr; v_ptr += num_links;
440  btVector3 * coriolis_bottom_linear = v_ptr; v_ptr += num_links;
441 
442  // top left, top right and bottom left blocks of Ihat_i^A.
443  // bottom right block = transpose of top left block and is not stored.
444  // Note: the top right and bottom left blocks are always symmetric matrices, but we don't make use of this fact currently.
445  btMatrix3x3 * inertia_top_left = &scratch_m[num_links + 1];
446  btMatrix3x3 * inertia_top_right = &scratch_m[2*num_links + 2];
447  btMatrix3x3 * inertia_bottom_left = &scratch_m[3*num_links + 3];
448 
449  // Cached 3x3 rotation matrices from parent frame to this frame.
450  btMatrix3x3 * rot_from_parent = &matrix_buf[0];
451  btMatrix3x3 * rot_from_world = &scratch_m[0];
452 
453  // hhat_i, ahat_i
454  // hhat is NOT stored for the base (but ahat is)
455  btVector3 * h_top = num_links > 0 ? &vector_buf[0] : 0;
456  btVector3 * h_bottom = num_links > 0 ? &vector_buf[num_links] : 0;
457  btVector3 * accel_top = v_ptr; v_ptr += num_links + 1;
458  btVector3 * accel_bottom = v_ptr; v_ptr += num_links + 1;
459 
460  // Y_i, D_i
461  btScalar * Y = r_ptr; r_ptr += num_links;
462  btScalar * D = num_links > 0 ? &m_real_buf[6 + num_links] : 0;
463 
464  // ptr to the joint accel part of the output
465  btScalar * joint_accel = output + 6;
466 
467 
468  // Start of the algorithm proper.
469 
470  // First 'upward' loop.
471  // Combines CompTreeLinkVelocities and InitTreeLinks from Mirtich.
472 
473  rot_from_parent[0] = btMatrix3x3(base_quat);
474 
475  vel_top_angular[0] = rot_from_parent[0] * base_omega;
476  vel_bottom_linear[0] = rot_from_parent[0] * base_vel;
477 
478  if (fixed_base) {
479  zero_acc_top_angular[0] = zero_acc_bottom_linear[0] = btVector3(0,0,0);
480  } else {
481  zero_acc_top_angular[0] = - (rot_from_parent[0] * (base_force
482  - base_mass*(DAMPING_K1_LINEAR+DAMPING_K2_LINEAR*base_vel.norm())*base_vel));
483 
484  zero_acc_bottom_linear[0] =
485  - (rot_from_parent[0] * base_torque);
486 
487  if (m_useGyroTerm)
488  zero_acc_bottom_linear[0]+=vel_top_angular[0].cross( base_inertia * vel_top_angular[0] );
489 
490  zero_acc_bottom_linear[0] += base_inertia * vel_top_angular[0] * (DAMPING_K1_ANGULAR + DAMPING_K2_ANGULAR*vel_top_angular[0].norm());
491 
492  }
493 
494 
495 
496  inertia_top_left[0] = btMatrix3x3(0,0,0,0,0,0,0,0,0);//::Zero();
497 
498 
499  inertia_top_right[0].setValue(base_mass, 0, 0,
500  0, base_mass, 0,
501  0, 0, base_mass);
502  inertia_bottom_left[0].setValue(base_inertia[0], 0, 0,
503  0, base_inertia[1], 0,
504  0, 0, base_inertia[2]);
505 
506  rot_from_world[0] = rot_from_parent[0];
507 
508  for (int i = 0; i < num_links; ++i) {
509  const int parent = links[i].parent;
510  rot_from_parent[i+1] = btMatrix3x3(links[i].cached_rot_parent_to_this);
511 
512 
513  rot_from_world[i+1] = rot_from_parent[i+1] * rot_from_world[parent+1];
514 
515  // vhat_i = i_xhat_p(i) * vhat_p(i)
516  SpatialTransform(rot_from_parent[i+1], links[i].cached_r_vector,
517  vel_top_angular[parent+1], vel_bottom_linear[parent+1],
518  vel_top_angular[i+1], vel_bottom_linear[i+1]);
519 
520  // we can now calculate chat_i
521  // remember vhat_i is really vhat_p(i) (but in current frame) at this point
522  coriolis_bottom_linear[i] = vel_top_angular[i+1].cross(vel_top_angular[i+1].cross(links[i].cached_r_vector))
523  + 2 * vel_top_angular[i+1].cross(links[i].axis_bottom) * getJointVel(i);
524  if (links[i].is_revolute) {
525  coriolis_top_angular[i] = vel_top_angular[i+1].cross(links[i].axis_top) * getJointVel(i);
526  coriolis_bottom_linear[i] += (getJointVel(i) * getJointVel(i)) * links[i].axis_top.cross(links[i].axis_bottom);
527  } else {
528  coriolis_top_angular[i] = btVector3(0,0,0);
529  }
530 
531  // now set vhat_i to its true value by doing
532  // vhat_i += qidot * shat_i
533  vel_top_angular[i+1] += getJointVel(i) * links[i].axis_top;
534  vel_bottom_linear[i+1] += getJointVel(i) * links[i].axis_bottom;
535 
536  // calculate zhat_i^A
537  zero_acc_top_angular[i+1] = - (rot_from_world[i+1] * (links[i].applied_force));
538  zero_acc_top_angular[i+1] += links[i].mass * (DAMPING_K1_LINEAR + DAMPING_K2_LINEAR*vel_bottom_linear[i+1].norm()) * vel_bottom_linear[i+1];
539 
540  zero_acc_bottom_linear[i+1] =
541  - (rot_from_world[i+1] * links[i].applied_torque);
542  if (m_useGyroTerm)
543  {
544  zero_acc_bottom_linear[i+1] += vel_top_angular[i+1].cross( links[i].inertia * vel_top_angular[i+1] );
545  }
546 
547  zero_acc_bottom_linear[i+1] += links[i].inertia * vel_top_angular[i+1] * (DAMPING_K1_ANGULAR + DAMPING_K2_ANGULAR*vel_top_angular[i+1].norm());
548 
549  // calculate Ihat_i^A
550  inertia_top_left[i+1] = btMatrix3x3(0,0,0,0,0,0,0,0,0);//::Zero();
551  inertia_top_right[i+1].setValue(links[i].mass, 0, 0,
552  0, links[i].mass, 0,
553  0, 0, links[i].mass);
554  inertia_bottom_left[i+1].setValue(links[i].inertia[0], 0, 0,
555  0, links[i].inertia[1], 0,
556  0, 0, links[i].inertia[2]);
557  }
558 
559 
560  // 'Downward' loop.
561  // (part of TreeForwardDynamics in Mirtich.)
562  for (int i = num_links - 1; i >= 0; --i) {
563 
564  h_top[i] = inertia_top_left[i+1] * links[i].axis_top + inertia_top_right[i+1] * links[i].axis_bottom;
565  h_bottom[i] = inertia_bottom_left[i+1] * links[i].axis_top + inertia_top_left[i+1].transpose() * links[i].axis_bottom;
566  btScalar val = SpatialDotProduct(links[i].axis_top, links[i].axis_bottom, h_top[i], h_bottom[i]);
567  D[i] = val;
568  Y[i] = links[i].joint_torque
569  - SpatialDotProduct(links[i].axis_top, links[i].axis_bottom, zero_acc_top_angular[i+1], zero_acc_bottom_linear[i+1])
570  - SpatialDotProduct(h_top[i], h_bottom[i], coriolis_top_angular[i], coriolis_bottom_linear[i]);
571 
572  const int parent = links[i].parent;
573 
574 
575  // Ip += pXi * (Ii - hi hi' / Di) * iXp
576  const btScalar one_over_di = 1.0f / D[i];
577 
578 
579 
580 
581  const btMatrix3x3 TL = inertia_top_left[i+1] - vecMulVecTranspose(one_over_di * h_top[i] , h_bottom[i]);
582  const btMatrix3x3 TR = inertia_top_right[i+1] - vecMulVecTranspose(one_over_di * h_top[i] , h_top[i]);
583  const btMatrix3x3 BL = inertia_bottom_left[i+1]- vecMulVecTranspose(one_over_di * h_bottom[i] , h_bottom[i]);
584 
585 
586  btMatrix3x3 r_cross;
587  r_cross.setValue(
588  0, -links[i].cached_r_vector[2], links[i].cached_r_vector[1],
589  links[i].cached_r_vector[2], 0, -links[i].cached_r_vector[0],
590  -links[i].cached_r_vector[1], links[i].cached_r_vector[0], 0);
591 
592  inertia_top_left[parent+1] += rot_from_parent[i+1].transpose() * ( TL - TR * r_cross ) * rot_from_parent[i+1];
593  inertia_top_right[parent+1] += rot_from_parent[i+1].transpose() * TR * rot_from_parent[i+1];
594  inertia_bottom_left[parent+1] += rot_from_parent[i+1].transpose() *
595  (r_cross * (TL - TR * r_cross) + BL - TL.transpose() * r_cross) * rot_from_parent[i+1];
596 
597 
598  // Zp += pXi * (Zi + Ii*ci + hi*Yi/Di)
599  btVector3 in_top, in_bottom, out_top, out_bottom;
600  const btScalar Y_over_D = Y[i] * one_over_di;
601  in_top = zero_acc_top_angular[i+1]
602  + inertia_top_left[i+1] * coriolis_top_angular[i]
603  + inertia_top_right[i+1] * coriolis_bottom_linear[i]
604  + Y_over_D * h_top[i];
605  in_bottom = zero_acc_bottom_linear[i+1]
606  + inertia_bottom_left[i+1] * coriolis_top_angular[i]
607  + inertia_top_left[i+1].transpose() * coriolis_bottom_linear[i]
608  + Y_over_D * h_bottom[i];
609  InverseSpatialTransform(rot_from_parent[i+1], links[i].cached_r_vector,
610  in_top, in_bottom, out_top, out_bottom);
611  zero_acc_top_angular[parent+1] += out_top;
612  zero_acc_bottom_linear[parent+1] += out_bottom;
613  }
614 
615 
616  // Second 'upward' loop
617  // (part of TreeForwardDynamics in Mirtich)
618 
619  if (fixed_base)
620  {
621  accel_top[0] = accel_bottom[0] = btVector3(0,0,0);
622  }
623  else
624  {
625  if (num_links > 0)
626  {
627  //Matrix<btScalar, 6, 6> Imatrix;
628  //Imatrix.block<3,3>(0,0) = inertia_top_left[0];
629  //Imatrix.block<3,3>(3,0) = inertia_bottom_left[0];
630  //Imatrix.block<3,3>(0,3) = inertia_top_right[0];
631  //Imatrix.block<3,3>(3,3) = inertia_top_left[0].transpose();
632  //cached_imatrix_lu.reset(new Eigen::LU<Matrix<btScalar, 6, 6> >(Imatrix)); // TODO: Avoid memory allocation here?
633 
634  cached_inertia_top_left = inertia_top_left[0];
635  cached_inertia_top_right = inertia_top_right[0];
636  cached_inertia_lower_left = inertia_bottom_left[0];
637  cached_inertia_lower_right= inertia_top_left[0].transpose();
638 
639  }
640  btVector3 rhs_top (zero_acc_top_angular[0][0], zero_acc_top_angular[0][1], zero_acc_top_angular[0][2]);
641  btVector3 rhs_bot (zero_acc_bottom_linear[0][0], zero_acc_bottom_linear[0][1], zero_acc_bottom_linear[0][2]);
642  float result[6];
643 
644  solveImatrix(rhs_top, rhs_bot, result);
645 // printf("result=%f,%f,%f,%f,%f,%f\n",result[0],result[0],result[0],result[0],result[0],result[0]);
646  for (int i = 0; i < 3; ++i) {
647  accel_top[0][i] = -result[i];
648  accel_bottom[0][i] = -result[i+3];
649  }
650 
651  }
652 
653  // now do the loop over the links
654  for (int i = 0; i < num_links; ++i) {
655  const int parent = links[i].parent;
656  SpatialTransform(rot_from_parent[i+1], links[i].cached_r_vector,
657  accel_top[parent+1], accel_bottom[parent+1],
658  accel_top[i+1], accel_bottom[i+1]);
659  joint_accel[i] = (Y[i] - SpatialDotProduct(h_top[i], h_bottom[i], accel_top[i+1], accel_bottom[i+1])) / D[i];
660  accel_top[i+1] += coriolis_top_angular[i] + joint_accel[i] * links[i].axis_top;
661  accel_bottom[i+1] += coriolis_bottom_linear[i] + joint_accel[i] * links[i].axis_bottom;
662  }
663 
664  // transform base accelerations back to the world frame.
665  btVector3 omegadot_out = rot_from_parent[0].transpose() * accel_top[0];
666  output[0] = omegadot_out[0];
667  output[1] = omegadot_out[1];
668  output[2] = omegadot_out[2];
669 
670  btVector3 vdot_out = rot_from_parent[0].transpose() * accel_bottom[0];
671  output[3] = vdot_out[0];
672  output[4] = vdot_out[1];
673  output[5] = vdot_out[2];
674  // Final step: add the accelerations (times dt) to the velocities.
675  applyDeltaVee(output, dt);
676 
677 
678 }
679 
680 
681 
682 void btMultiBody::solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, float result[6]) const
683 {
684  int num_links = getNumLinks();
686  if (num_links == 0)
687  {
688  // in the case of 0 links (i.e. a plain rigid body, not a multibody) rhs * invI is easier
689  result[0] = rhs_bot[0] / base_inertia[0];
690  result[1] = rhs_bot[1] / base_inertia[1];
691  result[2] = rhs_bot[2] / base_inertia[2];
692  result[3] = rhs_top[0] / base_mass;
693  result[4] = rhs_top[1] / base_mass;
694  result[5] = rhs_top[2] / base_mass;
695  } else
696  {
702  tmp = invIupper_right * cached_inertia_lower_right;
703  btMatrix3x3 invI_upper_left = (tmp * Binv);
704  btMatrix3x3 invI_lower_right = (invI_upper_left).transpose();
705  tmp = cached_inertia_top_left * invI_upper_left;
706  tmp[0][0]-= 1.0;
707  tmp[1][1]-= 1.0;
708  tmp[2][2]-= 1.0;
709  btMatrix3x3 invI_lower_left = (Binv * tmp);
710 
711  //multiply result = invI * rhs
712  {
713  btVector3 vtop = invI_upper_left*rhs_top;
714  btVector3 tmp;
715  tmp = invIupper_right * rhs_bot;
716  vtop += tmp;
717  btVector3 vbot = invI_lower_left*rhs_top;
718  tmp = invI_lower_right * rhs_bot;
719  vbot += tmp;
720  result[0] = vtop[0];
721  result[1] = vtop[1];
722  result[2] = vtop[2];
723  result[3] = vbot[0];
724  result[4] = vbot[1];
725  result[5] = vbot[2];
726  }
727 
728  }
729 }
730 
731 
734 {
735  // Temporary matrices/vectors -- use scratch space from caller
736  // so that we don't have to keep reallocating every frame
737  int num_links = getNumLinks();
738  scratch_r.resize(num_links);
739  scratch_v.resize(4*num_links + 4);
740 
741  btScalar * r_ptr = num_links == 0 ? 0 : &scratch_r[0];
742  btVector3 * v_ptr = &scratch_v[0];
743 
744  // zhat_i^A (scratch space)
745  btVector3 * zero_acc_top_angular = v_ptr; v_ptr += num_links + 1;
746  btVector3 * zero_acc_bottom_linear = v_ptr; v_ptr += num_links + 1;
747 
748  // rot_from_parent (cached from calcAccelerations)
749  const btMatrix3x3 * rot_from_parent = &matrix_buf[0];
750 
751  // hhat (cached), accel (scratch)
752  const btVector3 * h_top = num_links > 0 ? &vector_buf[0] : 0;
753  const btVector3 * h_bottom = num_links > 0 ? &vector_buf[num_links] : 0;
754  btVector3 * accel_top = v_ptr; v_ptr += num_links + 1;
755  btVector3 * accel_bottom = v_ptr; v_ptr += num_links + 1;
756 
757  // Y_i (scratch), D_i (cached)
758  btScalar * Y = r_ptr; r_ptr += num_links;
759  const btScalar * D = num_links > 0 ? &m_real_buf[6 + num_links] : 0;
760 
761  btAssert(num_links == 0 || r_ptr - &scratch_r[0] == scratch_r.size());
762  btAssert(v_ptr - &scratch_v[0] == scratch_v.size());
763 
764 
765 
766  // First 'upward' loop.
767  // Combines CompTreeLinkVelocities and InitTreeLinks from Mirtich.
768 
769  btVector3 input_force(force[3],force[4],force[5]);
770  btVector3 input_torque(force[0],force[1],force[2]);
771 
772  // Fill in zero_acc
773  // -- set to force/torque on the base, zero otherwise
774  if (fixed_base)
775  {
776  zero_acc_top_angular[0] = zero_acc_bottom_linear[0] = btVector3(0,0,0);
777  } else
778  {
779  zero_acc_top_angular[0] = - (rot_from_parent[0] * input_force);
780  zero_acc_bottom_linear[0] = - (rot_from_parent[0] * input_torque);
781  }
782  for (int i = 0; i < num_links; ++i)
783  {
784  zero_acc_top_angular[i+1] = zero_acc_bottom_linear[i+1] = btVector3(0,0,0);
785  }
786 
787  // 'Downward' loop.
788  for (int i = num_links - 1; i >= 0; --i)
789  {
790 
791  Y[i] = - SpatialDotProduct(links[i].axis_top, links[i].axis_bottom, zero_acc_top_angular[i+1], zero_acc_bottom_linear[i+1]);
792  Y[i] += force[6 + i]; // add joint torque
793 
794  const int parent = links[i].parent;
795 
796  // Zp += pXi * (Zi + hi*Yi/Di)
797  btVector3 in_top, in_bottom, out_top, out_bottom;
798  const btScalar Y_over_D = Y[i] / D[i];
799  in_top = zero_acc_top_angular[i+1] + Y_over_D * h_top[i];
800  in_bottom = zero_acc_bottom_linear[i+1] + Y_over_D * h_bottom[i];
801  InverseSpatialTransform(rot_from_parent[i+1], links[i].cached_r_vector,
802  in_top, in_bottom, out_top, out_bottom);
803  zero_acc_top_angular[parent+1] += out_top;
804  zero_acc_bottom_linear[parent+1] += out_bottom;
805  }
806 
807  // ptr to the joint accel part of the output
808  btScalar * joint_accel = output + 6;
809 
810  // Second 'upward' loop
811  if (fixed_base)
812  {
813  accel_top[0] = accel_bottom[0] = btVector3(0,0,0);
814  } else
815  {
816  btVector3 rhs_top (zero_acc_top_angular[0][0], zero_acc_top_angular[0][1], zero_acc_top_angular[0][2]);
817  btVector3 rhs_bot (zero_acc_bottom_linear[0][0], zero_acc_bottom_linear[0][1], zero_acc_bottom_linear[0][2]);
818 
819  float result[6];
820  solveImatrix(rhs_top,rhs_bot, result);
821  // printf("result=%f,%f,%f,%f,%f,%f\n",result[0],result[0],result[0],result[0],result[0],result[0]);
822 
823  for (int i = 0; i < 3; ++i) {
824  accel_top[0][i] = -result[i];
825  accel_bottom[0][i] = -result[i+3];
826  }
827 
828  }
829 
830  // now do the loop over the links
831  for (int i = 0; i < num_links; ++i) {
832  const int parent = links[i].parent;
833  SpatialTransform(rot_from_parent[i+1], links[i].cached_r_vector,
834  accel_top[parent+1], accel_bottom[parent+1],
835  accel_top[i+1], accel_bottom[i+1]);
836  joint_accel[i] = (Y[i] - SpatialDotProduct(h_top[i], h_bottom[i], accel_top[i+1], accel_bottom[i+1])) / D[i];
837  accel_top[i+1] += joint_accel[i] * links[i].axis_top;
838  accel_bottom[i+1] += joint_accel[i] * links[i].axis_bottom;
839  }
840 
841  // transform base accelerations back to the world frame.
842  btVector3 omegadot_out;
843  omegadot_out = rot_from_parent[0].transpose() * accel_top[0];
844  output[0] = omegadot_out[0];
845  output[1] = omegadot_out[1];
846  output[2] = omegadot_out[2];
847 
848  btVector3 vdot_out;
849  vdot_out = rot_from_parent[0].transpose() * accel_bottom[0];
850 
851  output[3] = vdot_out[0];
852  output[4] = vdot_out[1];
853  output[5] = vdot_out[2];
854 }
855 
857 {
858  int num_links = getNumLinks();
859  // step position by adding dt * velocity
860  btVector3 v = getBaseVel();
861  base_pos += dt * v;
862 
863  // "exponential map" method for the rotation
864  btVector3 base_omega = getBaseOmega();
865  const btScalar omega_norm = base_omega.norm();
866  const btScalar omega_times_dt = omega_norm * dt;
867  const btScalar SMALL_ROTATION_ANGLE = 0.02f; // Theoretically this should be ~ pow(FLT_EPSILON,0.25) which is ~ 0.0156
868  if (fabs(omega_times_dt) < SMALL_ROTATION_ANGLE)
869  {
870  const btScalar xsq = omega_times_dt * omega_times_dt; // |omega|^2 * dt^2
871  const btScalar sin_term = dt * (xsq / 48.0f - 0.5f); // -sin(0.5*dt*|omega|) / |omega|
872  const btScalar cos_term = 1.0f - xsq / 8.0f; // cos(0.5*dt*|omega|)
873  base_quat = base_quat * btQuaternion(sin_term * base_omega[0],sin_term * base_omega[1],sin_term * base_omega[2],cos_term);
874  } else
875  {
876  base_quat = base_quat * btQuaternion(base_omega / omega_norm,-omega_times_dt);
877  }
878 
879  // Make sure the quaternion represents a valid rotation.
880  // (Not strictly necessary, but helps prevent any round-off errors from building up.)
882 
883  // Finally we can update joint_pos for each of the links
884  for (int i = 0; i < num_links; ++i)
885  {
886  float jointVel = getJointVel(i);
887  links[i].joint_pos += dt * jointVel;
888  links[i].updateCache();
889  }
890 }
891 
893  const btVector3 &contact_point,
894  const btVector3 &normal,
895  btScalar *jac,
898  btAlignedObjectArray<btMatrix3x3> &scratch_m) const
899 {
900  // temporary space
901  int num_links = getNumLinks();
902  scratch_v.resize(2*num_links + 2);
903  scratch_m.resize(num_links + 1);
904 
905  btVector3 * v_ptr = &scratch_v[0];
906  btVector3 * p_minus_com = v_ptr; v_ptr += num_links + 1;
907  btVector3 * n_local = v_ptr; v_ptr += num_links + 1;
908  btAssert(v_ptr - &scratch_v[0] == scratch_v.size());
909 
910  scratch_r.resize(num_links);
911  btScalar * results = num_links > 0 ? &scratch_r[0] : 0;
912 
913  btMatrix3x3 * rot_from_world = &scratch_m[0];
914 
915  const btVector3 p_minus_com_world = contact_point - base_pos;
916 
917  rot_from_world[0] = btMatrix3x3(base_quat);
918 
919  p_minus_com[0] = rot_from_world[0] * p_minus_com_world;
920  n_local[0] = rot_from_world[0] * normal;
921 
922  // omega coeffients first.
923  btVector3 omega_coeffs;
924  omega_coeffs = p_minus_com_world.cross(normal);
925  jac[0] = omega_coeffs[0];
926  jac[1] = omega_coeffs[1];
927  jac[2] = omega_coeffs[2];
928  // then v coefficients
929  jac[3] = normal[0];
930  jac[4] = normal[1];
931  jac[5] = normal[2];
932 
933  // Set remaining jac values to zero for now.
934  for (int i = 6; i < 6 + num_links; ++i) {
935  jac[i] = 0;
936  }
937 
938  // Qdot coefficients, if necessary.
939  if (num_links > 0 && link > -1) {
940 
941  // TODO: speed this up -- don't calculate for links we don't need.
942  // (Also, we are making 3 separate calls to this function, for the normal & the 2 friction directions,
943  // which is resulting in repeated work being done...)
944 
945  // calculate required normals & positions in the local frames.
946  for (int i = 0; i < num_links; ++i) {
947 
948  // transform to local frame
949  const int parent = links[i].parent;
950  const btMatrix3x3 mtx(links[i].cached_rot_parent_to_this);
951  rot_from_world[i+1] = mtx * rot_from_world[parent+1];
952 
953  n_local[i+1] = mtx * n_local[parent+1];
954  p_minus_com[i+1] = mtx * p_minus_com[parent+1] - links[i].cached_r_vector;
955 
956  // calculate the jacobian entry
957  if (links[i].is_revolute) {
958  results[i] = n_local[i+1].dot( links[i].axis_top.cross(p_minus_com[i+1]) + links[i].axis_bottom );
959  } else {
960  results[i] = n_local[i+1].dot( links[i].axis_bottom );
961  }
962  }
963 
964  // Now copy through to output.
965  while (link != -1) {
966  jac[6 + link] = results[link];
967  link = links[link].parent;
968  }
969  }
970 }
971 
973 {
974  awake = true;
975 }
976 
978 {
979  awake = false;
980 }
981 
983 {
984  int num_links = getNumLinks();
985  extern bool gDisableDeactivation;
986  if (!can_sleep || gDisableDeactivation)
987  {
988  awake = true;
989  sleep_timer = 0;
990  return;
991  }
992 
993  // motion is computed as omega^2 + v^2 + (sum of squares of joint velocities)
994  btScalar motion = 0;
995  for (int i = 0; i < 6 + num_links; ++i) {
996  motion += m_real_buf[i] * m_real_buf[i];
997  }
998 
999  if (motion < SLEEP_EPSILON) {
1000  sleep_timer += timestep;
1001  if (sleep_timer > SLEEP_TIMEOUT) {
1002  goToSleep();
1003  }
1004  } else {
1005  sleep_timer = 0;
1006  if (!awake)
1007  wakeUp();
1008  }
1009 }
btMatrix3x3 inverse() const
Return the inverse of the matrix.
Definition: btMatrix3x3.h:1025
void calcAccelerationDeltas(const btScalar *force, btScalar *output, btAlignedObjectArray< btScalar > &scratch_r, btAlignedObjectArray< btVector3 > &scratch_v) const
bool m_useGyroTerm
Definition: btMultiBody.h:461
const btVector3 getBaseVel() const
Definition: btMultiBody.h:132
void setValue(const btScalar &_x, const btScalar &_y, const btScalar &_z)
Definition: btVector3.h:640
int getNumLinks() const
Definition: btMultiBody.h:112
btVector3 base_pos
Definition: btMultiBody.h:412
bool gDisableDeactivation
Definition: btRigidBody.cpp:26
btVector3 base_torque
Definition: btMultiBody.h:419
const btVector3 & getLinkForce(int i) const
#define btAssert(x)
Definition: btScalar.h:101
btVector3 localDirToWorld(int i, const btVector3 &vec) const
btAlignedObjectArray< btScalar > m_real_buf
Definition: btMultiBody.h:440
void addLinkForce(int i, const btVector3 &f)
btScalar getJointPos(int i) const
btMatrix3x3 cached_inertia_top_right
Definition: btMultiBody.h:447
btMatrix3x3 cached_inertia_lower_left
Definition: btMultiBody.h:448
btQuaternion inverse(const btQuaternion &q)
Return the inverse of a quaternion.
Definition: btQuaternion.h:849
btAlignedObjectArray< btVector3 > vector_buf
Definition: btMultiBody.h:441
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition: btVector3.h:235
void applyDeltaVee(const btScalar *delta_vee)
Definition: btMultiBody.h:269
void clearForcesAndTorques()
const btScalar & x() const
Return the x value.
Definition: btVector3.h:575
btVector3 quatRotate(const btQuaternion &rotation, const btVector3 &v)
Definition: btQuaternion.h:866
btVector3 getAngularMomentum() const
btAlignedObjectArray< btMatrix3x3 > matrix_buf
Definition: btMultiBody.h:442
int size() const
return the number of elements in the array
btQuaternion & normalize()
Normalize the quaternion Such that x^2 + y^2 + z^2 +w^2 = 1.
Definition: btQuaternion.h:332
const btVector3 & getLinkTorque(int i) const
void addLinkTorque(int i, const btVector3 &t)
static float4 fabs(const float4 &a)
void compTreeLinkVelocities(btVector3 *omega, btVector3 *vel) const
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
Definition: btVector3.h:377
void addJointTorque(int i, btScalar Q)
void setValue(const btScalar &xx, const btScalar &xy, const btScalar &xz, const btScalar &yx, const btScalar &yy, const btScalar &yz, const btScalar &zx, const btScalar &zy, const btScalar &zz)
Set the values of the matrix explicitly (row major)
Definition: btMatrix3x3.h:198
void solveImatrix(const btVector3 &rhs_top, const btVector3 &rhs_bot, float result[6]) const
const btVector3 & getRVector(int i) const
void setJointVel(int i, btScalar qdot)
void setJointPos(int i, btScalar q)
bool can_sleep
Definition: btMultiBody.h:455
btScalar sleep_timer
Definition: btMultiBody.h:456
void clearVelocities()
btScalar norm() const
Return the norm (length) of the vector.
Definition: btVector3.h:269
const btScalar & y() const
Return the y value.
Definition: btVector3.h:577
void checkMotionAndSleepIfRequired(btScalar timestep)
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
btScalar getLinkMass(int i) const
btQuaternion base_quat
Definition: btMultiBody.h:413
btVector3 base_inertia
Definition: btMultiBody.h:416
btMatrix3x3 vecMulVecTranspose(const btVector3 &v0, const btVector3 &v1Transposed)
bool fixed_base
Definition: btMultiBody.h:451
btVector3 getBaseOmega() const
Definition: btMultiBody.h:140
btAlignedObjectArray< btMultibodyLink > links
Definition: btMultiBody.h:421
btScalar m_linearDamping
Definition: btMultiBody.h:459
void resize(int newsize, const T &fillData=T())
btMatrix3x3 cached_inertia_top_left
Definition: btMultiBody.h:446
void setupPrismatic(int i, btScalar mass, const btVector3 &inertia, int parent, const btQuaternion &rot_parent_to_this, const btVector3 &joint_axis, const btVector3 &r_vector_when_q_zero, bool disableParentCollision=false)
void goToSleep()
btMatrix3x3 transpose() const
Return the transpose of the matrix.
Definition: btMatrix3x3.h:980
static float4 cross(const float4 &a, const float4 &b)
btMultiBody(int n_links, btScalar mass, const btVector3 &inertia, bool fixed_base_, bool can_sleep_)
Definition: btMultiBody.cpp:79
btVector3 worldPosToLocal(int i, const btVector3 &vec) const
const btQuaternion & getParentToLocalRot(int i) const
const Matrix3 transpose(const Matrix3 &mat)
Definition: neon/mat_aos.h:165
void fillContactJacobian(int link, const btVector3 &contact_point, const btVector3 &normal, btScalar *jac, btAlignedObjectArray< btScalar > &scratch_r, btAlignedObjectArray< btVector3 > &scratch_v, btAlignedObjectArray< btMatrix3x3 > &scratch_m) const
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition: btMatrix3x3.h:48
btVector3 worldDirToLocal(int i, const btVector3 &vec) const
const btVector3 & getLinkInertia(int i) const
void setupRevolute(int i, btScalar mass, const btVector3 &inertia, int parent, const btQuaternion &zero_rot_parent_to_this, const btVector3 &joint_axis, const btVector3 &parent_axis_position, const btVector3 &my_axis_position, bool disableParentCollision=false)
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
Definition: btQuaternion.h:48
btScalar getJointTorque(int i) const
const btQuaternion & getWorldToBaseRot() const
Definition: btMultiBody.h:136
void stepPositions(btScalar dt)
int getParent(int link_num) const
const btVector3 & getBasePos() const
Definition: btMultiBody.h:131
btVector3 localPosToWorld(int i, const btVector3 &vec) const
btVector3 base_force
Definition: btMultiBody.h:418
btScalar base_mass
Definition: btMultiBody.h:415
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:266
btScalar m_angularDamping
Definition: btMultiBody.h:460
void stepVelocities(btScalar dt, btAlignedObjectArray< btScalar > &scratch_r, btAlignedObjectArray< btVector3 > &scratch_v, btAlignedObjectArray< btMatrix3x3 > &scratch_m)
btScalar getJointVel(int i) const
btScalar getKineticEnergy() const
const btScalar & z() const
Return the z value.
Definition: btVector3.h:579
btMatrix3x3 cached_inertia_lower_right
Definition: btMultiBody.h:449