Bullet Collision Detection & Physics Library
btRaycastVehicle.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/
3  *
4  * Permission to use, copy, modify, distribute and sell this software
5  * and its documentation for any purpose is hereby granted without fee,
6  * provided that the above copyright notice appear in all copies.
7  * Erwin Coumans makes no representations about the suitability
8  * of this software for any purpose.
9  * It is provided "as is" without express or implied warranty.
10 */
11 
12 #include "LinearMath/btVector3.h"
13 #include "btRaycastVehicle.h"
14 
19 #include "btVehicleRaycaster.h"
20 #include "btWheelInfo.h"
21 #include "LinearMath/btMinMax.h"
24 
25 #define ROLLING_INFLUENCE_FIX
26 
27 
29 {
30  static btRigidBody s_fixed(0, 0,0);
31  s_fixed.setMassProps(btScalar(0.),btVector3(btScalar(0.),btScalar(0.),btScalar(0.)));
32  return s_fixed;
33 }
34 
36 :m_vehicleRaycaster(raycaster),
37 m_pitchControl(btScalar(0.))
38 {
39  m_chassisBody = chassis;
40  m_indexRightAxis = 0;
41  m_indexUpAxis = 2;
43  defaultInit(tuning);
44 }
45 
46 
48 {
49  (void)tuning;
52 
53 }
54 
55 
56 
58 {
59 }
60 
61 
62 //
63 // basically most of the code is general for 2 or 4 wheel vehicles, but some of it needs to be reviewed
64 //
65 btWheelInfo& btRaycastVehicle::addWheel( const btVector3& connectionPointCS, const btVector3& wheelDirectionCS0,const btVector3& wheelAxleCS, btScalar suspensionRestLength, btScalar wheelRadius,const btVehicleTuning& tuning, bool isFrontWheel)
66 {
67 
69 
70  ci.m_chassisConnectionCS = connectionPointCS;
71  ci.m_wheelDirectionCS = wheelDirectionCS0;
72  ci.m_wheelAxleCS = wheelAxleCS;
73  ci.m_suspensionRestLength = suspensionRestLength;
74  ci.m_wheelRadius = wheelRadius;
78  ci.m_frictionSlip = tuning.m_frictionSlip;
79  ci.m_bIsFrontWheel = isFrontWheel;
82 
84 
85  btWheelInfo& wheel = m_wheelInfo[getNumWheels()-1];
86 
87  updateWheelTransformsWS( wheel , false );
89  return wheel;
90 }
91 
92 
93 
94 
95 const btTransform& btRaycastVehicle::getWheelTransformWS( int wheelIndex ) const
96 {
97  btAssert(wheelIndex < getNumWheels());
98  const btWheelInfo& wheel = m_wheelInfo[wheelIndex];
99  return wheel.m_worldTransform;
100 
101 }
102 
103 void btRaycastVehicle::updateWheelTransform( int wheelIndex , bool interpolatedTransform)
104 {
105 
106  btWheelInfo& wheel = m_wheelInfo[ wheelIndex ];
107  updateWheelTransformsWS(wheel,interpolatedTransform);
109  const btVector3& right = wheel.m_raycastInfo.m_wheelAxleWS;
110  btVector3 fwd = up.cross(right);
111  fwd = fwd.normalize();
112 // up = right.cross(fwd);
113 // up.normalize();
114 
115  //rotate around steering over de wheelAxleWS
116  btScalar steering = wheel.m_steering;
117 
118  btQuaternion steeringOrn(up,steering);//wheel.m_steering);
119  btMatrix3x3 steeringMat(steeringOrn);
120 
121  btQuaternion rotatingOrn(right,-wheel.m_rotation);
122  btMatrix3x3 rotatingMat(rotatingOrn);
123 
124  btMatrix3x3 basis2;
125  basis2[0][m_indexRightAxis] = -right[0];
126  basis2[1][m_indexRightAxis] = -right[1];
127  basis2[2][m_indexRightAxis] = -right[2];
128 
129  basis2[0][m_indexUpAxis] = up[0];
130  basis2[1][m_indexUpAxis] = up[1];
131  basis2[2][m_indexUpAxis] = up[2];
132 
133  basis2[0][m_indexForwardAxis] = fwd[0];
134  basis2[1][m_indexForwardAxis] = fwd[1];
135  basis2[2][m_indexForwardAxis] = fwd[2];
136 
137  wheel.m_worldTransform.setBasis(steeringMat * rotatingMat * basis2);
140  );
141 }
142 
144 {
145 
146  int i;
147  for (i=0;i<m_wheelInfo.size(); i++)
148  {
149  btWheelInfo& wheel = m_wheelInfo[i];
152 
154  //wheel_info.setContactFriction(btScalar(0.0));
156  }
157 }
158 
159 void btRaycastVehicle::updateWheelTransformsWS(btWheelInfo& wheel , bool interpolatedTransform)
160 {
161  wheel.m_raycastInfo.m_isInContact = false;
162 
163  btTransform chassisTrans = getChassisWorldTransform();
164  if (interpolatedTransform && (getRigidBody()->getMotionState()))
165  {
166  getRigidBody()->getMotionState()->getWorldTransform(chassisTrans);
167  }
168 
169  wheel.m_raycastInfo.m_hardPointWS = chassisTrans( wheel.m_chassisConnectionPointCS );
170  wheel.m_raycastInfo.m_wheelDirectionWS = chassisTrans.getBasis() * wheel.m_wheelDirectionCS ;
171  wheel.m_raycastInfo.m_wheelAxleWS = chassisTrans.getBasis() * wheel.m_wheelAxleCS;
172 }
173 
175 {
176  updateWheelTransformsWS( wheel,false);
177 
178 
179  btScalar depth = -1;
180 
181  btScalar raylen = wheel.getSuspensionRestLength()+wheel.m_wheelsRadius;
182 
183  btVector3 rayvector = wheel.m_raycastInfo.m_wheelDirectionWS * (raylen);
184  const btVector3& source = wheel.m_raycastInfo.m_hardPointWS;
185  wheel.m_raycastInfo.m_contactPointWS = source + rayvector;
186  const btVector3& target = wheel.m_raycastInfo.m_contactPointWS;
187 
188  btScalar param = btScalar(0.);
189 
191 
193 
194  void* object = m_vehicleRaycaster->castRay(source,target,rayResults);
195 
196  wheel.m_raycastInfo.m_groundObject = 0;
197 
198  if (object)
199  {
200  param = rayResults.m_distFraction;
201  depth = raylen * rayResults.m_distFraction;
203  wheel.m_raycastInfo.m_isInContact = true;
204 
206  //wheel.m_raycastInfo.m_groundObject = object;
207 
208 
209  btScalar hitDistance = param*raylen;
210  wheel.m_raycastInfo.m_suspensionLength = hitDistance - wheel.m_wheelsRadius;
211  //clamp on max suspension travel
212 
213  btScalar minSuspensionLength = wheel.getSuspensionRestLength() - wheel.m_maxSuspensionTravelCm*btScalar(0.01);
214  btScalar maxSuspensionLength = wheel.getSuspensionRestLength()+ wheel.m_maxSuspensionTravelCm*btScalar(0.01);
215  if (wheel.m_raycastInfo.m_suspensionLength < minSuspensionLength)
216  {
217  wheel.m_raycastInfo.m_suspensionLength = minSuspensionLength;
218  }
219  if (wheel.m_raycastInfo.m_suspensionLength > maxSuspensionLength)
220  {
221  wheel.m_raycastInfo.m_suspensionLength = maxSuspensionLength;
222  }
223 
225 
227 
228  btVector3 chassis_velocity_at_contactPoint;
230 
231  chassis_velocity_at_contactPoint = getRigidBody()->getVelocityInLocalPoint(relpos);
232 
233  btScalar projVel = wheel.m_raycastInfo.m_contactNormalWS.dot( chassis_velocity_at_contactPoint );
234 
235  if ( denominator >= btScalar(-0.1))
236  {
239  }
240  else
241  {
242  btScalar inv = btScalar(-1.) / denominator;
243  wheel.m_suspensionRelativeVelocity = projVel * inv;
245  }
246 
247  } else
248  {
249  //put wheel info as in rest position
254  }
255 
256  return depth;
257 }
258 
259 
261 {
262  /*if (getRigidBody()->getMotionState())
263  {
264  btTransform chassisWorldTrans;
265  getRigidBody()->getMotionState()->getWorldTransform(chassisWorldTrans);
266  return chassisWorldTrans;
267  }
268  */
269 
270 
272 }
273 
274 
276 {
277  {
278  for (int i=0;i<getNumWheels();i++)
279  {
280  updateWheelTransform(i,false);
281  }
282  }
283 
284 
286 
287  const btTransform& chassisTrans = getChassisWorldTransform();
288 
289  btVector3 forwardW (
290  chassisTrans.getBasis()[0][m_indexForwardAxis],
291  chassisTrans.getBasis()[1][m_indexForwardAxis],
292  chassisTrans.getBasis()[2][m_indexForwardAxis]);
293 
294  if (forwardW.dot(getRigidBody()->getLinearVelocity()) < btScalar(0.))
295  {
297  }
298 
299  //
300  // simulate suspension
301  //
302 
303  int i=0;
304  for (i=0;i<m_wheelInfo.size();i++)
305  {
306  //btScalar depth;
307  //depth =
308  rayCast( m_wheelInfo[i]);
309  }
310 
311  updateSuspension(step);
312 
313 
314  for (i=0;i<m_wheelInfo.size();i++)
315  {
316  //apply suspension force
317  btWheelInfo& wheel = m_wheelInfo[i];
318 
319  btScalar suspensionForce = wheel.m_wheelsSuspensionForce;
320 
321  if (suspensionForce > wheel.m_maxSuspensionForce)
322  {
323  suspensionForce = wheel.m_maxSuspensionForce;
324  }
325  btVector3 impulse = wheel.m_raycastInfo.m_contactNormalWS * suspensionForce * step;
327 
328  getRigidBody()->applyImpulse(impulse, relpos);
329 
330  }
331 
332 
333 
334  updateFriction( step);
335 
336 
337  for (i=0;i<m_wheelInfo.size();i++)
338  {
339  btWheelInfo& wheel = m_wheelInfo[i];
342 
343  if (wheel.m_raycastInfo.m_isInContact)
344  {
345  const btTransform& chassisWorldTransform = getChassisWorldTransform();
346 
347  btVector3 fwd (
348  chassisWorldTransform.getBasis()[0][m_indexForwardAxis],
349  chassisWorldTransform.getBasis()[1][m_indexForwardAxis],
350  chassisWorldTransform.getBasis()[2][m_indexForwardAxis]);
351 
352  btScalar proj = fwd.dot(wheel.m_raycastInfo.m_contactNormalWS);
353  fwd -= wheel.m_raycastInfo.m_contactNormalWS * proj;
354 
355  btScalar proj2 = fwd.dot(vel);
356 
357  wheel.m_deltaRotation = (proj2 * step) / (wheel.m_wheelsRadius);
358  wheel.m_rotation += wheel.m_deltaRotation;
359 
360  } else
361  {
362  wheel.m_rotation += wheel.m_deltaRotation;
363  }
364 
365  wheel.m_deltaRotation *= btScalar(0.99);//damping of rotation when not in contact
366 
367  }
368 
369 
370 
371 }
372 
373 
375 {
376  btAssert(wheel>=0 && wheel < getNumWheels());
377 
378  btWheelInfo& wheelInfo = getWheelInfo(wheel);
379  wheelInfo.m_steering = steering;
380 }
381 
382 
383 
385 {
386  return getWheelInfo(wheel).m_steering;
387 }
388 
389 
391 {
392  btAssert(wheel>=0 && wheel < getNumWheels());
393  btWheelInfo& wheelInfo = getWheelInfo(wheel);
394  wheelInfo.m_engineForce = force;
395 }
396 
397 
399 {
400  btAssert((index >= 0) && (index < getNumWheels()));
401 
402  return m_wheelInfo[index];
403 }
404 
406 {
407  btAssert((index >= 0) && (index < getNumWheels()));
408 
409  return m_wheelInfo[index];
410 }
411 
412 void btRaycastVehicle::setBrake(btScalar brake,int wheelIndex)
413 {
414  btAssert((wheelIndex >= 0) && (wheelIndex < getNumWheels()));
415  getWheelInfo(wheelIndex).m_brake = brake;
416 }
417 
418 
420 {
421  (void)deltaTime;
422 
423  btScalar chassisMass = btScalar(1.) / m_chassisBody->getInvMass();
424 
425  for (int w_it=0; w_it<getNumWheels(); w_it++)
426  {
427  btWheelInfo &wheel_info = m_wheelInfo[w_it];
428 
429  if ( wheel_info.m_raycastInfo.m_isInContact )
430  {
431  btScalar force;
432  // Spring
433  {
434  btScalar susp_length = wheel_info.getSuspensionRestLength();
435  btScalar current_length = wheel_info.m_raycastInfo.m_suspensionLength;
436 
437  btScalar length_diff = (susp_length - current_length);
438 
439  force = wheel_info.m_suspensionStiffness
440  * length_diff * wheel_info.m_clippedInvContactDotSuspension;
441  }
442 
443  // Damper
444  {
445  btScalar projected_rel_vel = wheel_info.m_suspensionRelativeVelocity;
446  {
447  btScalar susp_damping;
448  if ( projected_rel_vel < btScalar(0.0) )
449  {
450  susp_damping = wheel_info.m_wheelsDampingCompression;
451  }
452  else
453  {
454  susp_damping = wheel_info.m_wheelsDampingRelaxation;
455  }
456  force -= susp_damping * projected_rel_vel;
457  }
458  }
459 
460  // RESULT
461  wheel_info.m_wheelsSuspensionForce = force * chassisMass;
462  if (wheel_info.m_wheelsSuspensionForce < btScalar(0.))
463  {
464  wheel_info.m_wheelsSuspensionForce = btScalar(0.);
465  }
466  }
467  else
468  {
469  wheel_info.m_wheelsSuspensionForce = btScalar(0.0);
470  }
471  }
472 
473 }
474 
475 
477 {
484 
485 
486  btWheelContactPoint(btRigidBody* body0,btRigidBody* body1,const btVector3& frictionPosWorld,const btVector3& frictionDirectionWorld, btScalar maxImpulse)
487  :m_body0(body0),
488  m_body1(body1),
489  m_frictionPositionWorld(frictionPosWorld),
490  m_frictionDirectionWorld(frictionDirectionWorld),
491  m_maxImpulse(maxImpulse)
492  {
493  btScalar denom0 = body0->computeImpulseDenominator(frictionPosWorld,frictionDirectionWorld);
494  btScalar denom1 = body1->computeImpulseDenominator(frictionPosWorld,frictionDirectionWorld);
495  btScalar relaxation = 1.f;
496  m_jacDiagABInv = relaxation/(denom0+denom1);
497  }
498 
499 
500 
501 };
502 
503 btScalar calcRollingFriction(btWheelContactPoint& contactPoint, int numWheelsOnGround);
504 btScalar calcRollingFriction(btWheelContactPoint& contactPoint, int numWheelsOnGround)
505 {
506 
507  btScalar j1=0.f;
508 
509  const btVector3& contactPosWorld = contactPoint.m_frictionPositionWorld;
510 
511  btVector3 rel_pos1 = contactPosWorld - contactPoint.m_body0->getCenterOfMassPosition();
512  btVector3 rel_pos2 = contactPosWorld - contactPoint.m_body1->getCenterOfMassPosition();
513 
514  btScalar maxImpulse = contactPoint.m_maxImpulse;
515 
516  btVector3 vel1 = contactPoint.m_body0->getVelocityInLocalPoint(rel_pos1);
517  btVector3 vel2 = contactPoint.m_body1->getVelocityInLocalPoint(rel_pos2);
518  btVector3 vel = vel1 - vel2;
519 
520  btScalar vrel = contactPoint.m_frictionDirectionWorld.dot(vel);
521 
522  // calculate j that moves us to zero relative velocity
523  j1 = -vrel * contactPoint.m_jacDiagABInv/btScalar(numWheelsOnGround);
524  btSetMin(j1, maxImpulse);
525  btSetMax(j1, -maxImpulse);
526 
527  return j1;
528 }
529 
530 
531 
532 
535 {
536 
537  //calculate the impulse, so that the wheels don't move sidewards
538  int numWheel = getNumWheels();
539  if (!numWheel)
540  return;
541 
542  m_forwardWS.resize(numWheel);
543  m_axle.resize(numWheel);
544  m_forwardImpulse.resize(numWheel);
545  m_sideImpulse.resize(numWheel);
546 
547  int numWheelsOnGround = 0;
548 
549 
550  //collapse all those loops into one!
551  for (int i=0;i<getNumWheels();i++)
552  {
553  btWheelInfo& wheelInfo = m_wheelInfo[i];
554  class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
555  if (groundObject)
556  numWheelsOnGround++;
557  m_sideImpulse[i] = btScalar(0.);
558  m_forwardImpulse[i] = btScalar(0.);
559 
560  }
561 
562  {
563 
564  for (int i=0;i<getNumWheels();i++)
565  {
566 
567  btWheelInfo& wheelInfo = m_wheelInfo[i];
568 
569  class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
570 
571  if (groundObject)
572  {
573 
574  const btTransform& wheelTrans = getWheelTransformWS( i );
575 
576  btMatrix3x3 wheelBasis0 = wheelTrans.getBasis();
577  m_axle[i] = -btVector3(
578  wheelBasis0[0][m_indexRightAxis],
579  wheelBasis0[1][m_indexRightAxis],
580  wheelBasis0[2][m_indexRightAxis]);
581 
582  const btVector3& surfNormalWS = wheelInfo.m_raycastInfo.m_contactNormalWS;
583  btScalar proj = m_axle[i].dot(surfNormalWS);
584  m_axle[i] -= surfNormalWS * proj;
585  m_axle[i] = m_axle[i].normalize();
586 
587  m_forwardWS[i] = surfNormalWS.cross(m_axle[i]);
588  m_forwardWS[i].normalize();
589 
590 
592  *groundObject, wheelInfo.m_raycastInfo.m_contactPointWS,
593  btScalar(0.), m_axle[i],m_sideImpulse[i],timeStep);
594 
596 
597  }
598 
599 
600  }
601  }
602 
603  btScalar sideFactor = btScalar(1.);
604  btScalar fwdFactor = 0.5;
605 
606  bool sliding = false;
607  {
608  for (int wheel =0;wheel <getNumWheels();wheel++)
609  {
610  btWheelInfo& wheelInfo = m_wheelInfo[wheel];
611  class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
612 
613  btScalar rollingFriction = 0.f;
614 
615  if (groundObject)
616  {
617  if (wheelInfo.m_engineForce != 0.f)
618  {
619  rollingFriction = wheelInfo.m_engineForce* timeStep;
620  } else
621  {
622  btScalar defaultRollingFrictionImpulse = 0.f;
623  btScalar maxImpulse = wheelInfo.m_brake ? wheelInfo.m_brake : defaultRollingFrictionImpulse;
624  btWheelContactPoint contactPt(m_chassisBody,groundObject,wheelInfo.m_raycastInfo.m_contactPointWS,m_forwardWS[wheel],maxImpulse);
625  btAssert(numWheelsOnGround > 0);
626  rollingFriction = calcRollingFriction(contactPt, numWheelsOnGround);
627  }
628  }
629 
630  //switch between active rolling (throttle), braking and non-active rolling friction (no throttle/break)
631 
632 
633 
634 
635  m_forwardImpulse[wheel] = btScalar(0.);
636  m_wheelInfo[wheel].m_skidInfo= btScalar(1.);
637 
638  if (groundObject)
639  {
640  m_wheelInfo[wheel].m_skidInfo= btScalar(1.);
641 
642  btScalar maximp = wheelInfo.m_wheelsSuspensionForce * timeStep * wheelInfo.m_frictionSlip;
643  btScalar maximpSide = maximp;
644 
645  btScalar maximpSquared = maximp * maximpSide;
646 
647 
648  m_forwardImpulse[wheel] = rollingFriction;//wheelInfo.m_engineForce* timeStep;
649 
650  btScalar x = (m_forwardImpulse[wheel] ) * fwdFactor;
651  btScalar y = (m_sideImpulse[wheel] ) * sideFactor;
652 
653  btScalar impulseSquared = (x*x + y*y);
654 
655  if (impulseSquared > maximpSquared)
656  {
657  sliding = true;
658 
659  btScalar factor = maximp / btSqrt(impulseSquared);
660 
661  m_wheelInfo[wheel].m_skidInfo *= factor;
662  }
663  }
664 
665  }
666  }
667 
668 
669 
670 
671  if (sliding)
672  {
673  for (int wheel = 0;wheel < getNumWheels(); wheel++)
674  {
675  if (m_sideImpulse[wheel] != btScalar(0.))
676  {
677  if (m_wheelInfo[wheel].m_skidInfo< btScalar(1.))
678  {
679  m_forwardImpulse[wheel] *= m_wheelInfo[wheel].m_skidInfo;
680  m_sideImpulse[wheel] *= m_wheelInfo[wheel].m_skidInfo;
681  }
682  }
683  }
684  }
685 
686  // apply the impulses
687  {
688  for (int wheel = 0;wheel<getNumWheels() ; wheel++)
689  {
690  btWheelInfo& wheelInfo = m_wheelInfo[wheel];
691 
692  btVector3 rel_pos = wheelInfo.m_raycastInfo.m_contactPointWS -
694 
695  if (m_forwardImpulse[wheel] != btScalar(0.))
696  {
697  m_chassisBody->applyImpulse(m_forwardWS[wheel]*(m_forwardImpulse[wheel]),rel_pos);
698  }
699  if (m_sideImpulse[wheel] != btScalar(0.))
700  {
701  class btRigidBody* groundObject = (class btRigidBody*) m_wheelInfo[wheel].m_raycastInfo.m_groundObject;
702 
703  btVector3 rel_pos2 = wheelInfo.m_raycastInfo.m_contactPointWS -
704  groundObject->getCenterOfMassPosition();
705 
706 
707  btVector3 sideImp = m_axle[wheel] * m_sideImpulse[wheel];
708 
709 #if defined ROLLING_INFLUENCE_FIX // fix. It only worked if car's up was along Y - VT.
711  rel_pos -= vChassisWorldUp * (vChassisWorldUp.dot(rel_pos) * (1.f-wheelInfo.m_rollInfluence));
712 #else
713  rel_pos[m_indexUpAxis] *= wheelInfo.m_rollInfluence;
714 #endif
715  m_chassisBody->applyImpulse(sideImp,rel_pos);
716 
717  //apply friction impulse on the ground
718  groundObject->applyImpulse(-sideImp,rel_pos2);
719  }
720  }
721  }
722 
723 
724 }
725 
726 
727 
729 {
730 
731  for (int v=0;v<this->getNumWheels();v++)
732  {
733  btVector3 wheelColor(0,1,1);
734  if (getWheelInfo(v).m_raycastInfo.m_isInContact)
735  {
736  wheelColor.setValue(0,0,1);
737  } else
738  {
739  wheelColor.setValue(1,0,1);
740  }
741 
743 
744  btVector3 axle = btVector3(
748 
749  //debug wheels (cylinders)
750  debugDrawer->drawLine(wheelPosWS,wheelPosWS+axle,wheelColor);
751  debugDrawer->drawLine(wheelPosWS,getWheelInfo(v).m_raycastInfo.m_contactPointWS,wheelColor);
752 
753  }
754 }
755 
756 
758 {
759 // RayResultCallback& resultCallback;
760 
761  btCollisionWorld::ClosestRayResultCallback rayCallback(from,to);
762 
763  m_dynamicsWorld->rayTest(from, to, rayCallback);
764 
765  if (rayCallback.hasHit())
766  {
767 
768  const btRigidBody* body = btRigidBody::upcast(rayCallback.m_collisionObject);
769  if (body && body->hasContactResponse())
770  {
771  result.m_hitPointInWorld = rayCallback.m_hitPointWorld;
772  result.m_hitNormalInWorld = rayCallback.m_hitNormalWorld;
773  result.m_hitNormalInWorld.normalize();
774  result.m_distFraction = rayCallback.m_closestHitFraction;
775  return (void*)body;
776  }
777  }
778  return 0;
779 }
780 
void setOrigin(const btVector3 &origin)
Set the translational element.
Definition: btTransform.h:150
btScalar getInvMass() const
Definition: btRigidBody.h:273
static const btRigidBody * upcast(const btCollisionObject *colObj)
to keep collision detection and dynamics separate we don&#39;t store a rigidbody pointer but a rigidbody ...
Definition: btRigidBody.h:203
btTransform m_worldTransform
Definition: btWheelInfo.h:55
virtual ~btRaycastVehicle()
void setSteeringValue(btScalar steering, int wheel)
void push_back(const T &_Val)
const btTransform & getWheelTransformWS(int wheelIndex) const
btAlignedObjectArray< btScalar > m_sideImpulse
void setValue(const btScalar &_x, const btScalar &_y, const btScalar &_z)
Definition: btVector3.h:652
btVector3 m_wheelDirectionWS
Definition: btWheelInfo.h:47
btWheelContactPoint(btRigidBody *body0, btRigidBody *body1, const btVector3 &frictionPosWorld, const btVector3 &frictionDirectionWorld, btScalar maxImpulse)
btScalar getSuspensionRestLength() const
Definition: btWheelInfo.cpp:15
btScalar m_suspensionRelativeVelocity
Definition: btWheelInfo.h:113
btScalar m_wheelsSuspensionForce
Definition: btWheelInfo.h:115
static btRigidBody & getFixedBody()
btScalar m_rotation
Definition: btWheelInfo.h:69
virtual void * castRay(const btVector3 &from, const btVector3 &to, btVehicleRaycasterResult &result)
btVector3 m_chassisConnectionPointCS
Definition: btWheelInfo.h:57
void setBasis(const btMatrix3x3 &basis)
Set the rotational element by btMatrix3x3.
Definition: btTransform.h:159
virtual void drawLine(const btVector3 &from, const btVector3 &to, const btVector3 &color)=0
void defaultInit(const btVehicleTuning &tuning)
btScalar m_maxSuspensionTravelCm
Definition: btWheelInfo.h:61
btScalar m_currentVehicleSpeedKmHour
btAlignedObjectArray< btWheelInfo > m_wheelInfo
btScalar m_frictionSlip
Definition: btWheelInfo.h:67
btScalar btSqrt(btScalar y)
Definition: btScalar.h:444
#define btAssert(x)
Definition: btScalar.h:131
const btCollisionObject * m_collisionObject
btVehicleRaycaster * m_vehicleRaycaster
btScalar computeImpulseDenominator(const btVector3 &pos, const btVector3 &normal) const
Definition: btRigidBody.h:403
void applyEngineForce(btScalar force, int wheel)
void debugDraw(btIDebugDraw *debugDrawer)
btActionInterface interface
btVector3 getColumn(int i) const
Get a column of the matrix as a vector.
Definition: btMatrix3x3.h:134
btTransform m_worldTransform
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition: btVector3.h:235
btWheelInfo contains information per wheel about friction and suspension.
Definition: btWheelInfo.h:38
bool hasContactResponse() const
virtual void updateVehicle(btScalar step)
btVector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
Definition: btVector3.h:309
btVector3 getVelocityInLocalPoint(const btVector3 &rel_pos) const
Definition: btRigidBody.h:382
const btTransform & getChassisWorldTransform() const
void btSetMin(T &a, const T &b)
Definition: btMinMax.h:41
btScalar m_suspensionStiffness
Definition: btWheelInfo.h:64
const btWheelInfo & getWheelInfo(int index) const
int size() const
return the number of elements in the array
btVector3 & getOrigin()
Return the origin vector translation.
Definition: btTransform.h:117
void resolveSingleBilateral(btRigidBody &body1, const btVector3 &pos1, btRigidBody &body2, const btVector3 &pos2, btScalar distance, const btVector3 &normal, btScalar &impulse, btScalar timeStep)
resolveSingleBilateral is an obsolete methods used for vehicle friction between two dynamic objects ...
const btTransform & getCenterOfMassTransform() const
Definition: btRigidBody.h:359
btScalar rayCast(btWheelInfo &wheel)
btVector3 m_wheelDirectionCS
Definition: btWheelInfo.h:58
btScalar m_wheelsRadius
Definition: btWheelInfo.h:63
btScalar m_steering
Definition: btWheelInfo.h:68
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
Definition: btVector3.h:389
void updateWheelTransformsWS(btWheelInfo &wheel, bool interpolatedTransform=true)
btMatrix3x3 & getBasis()
Return the basis matrix for the rotation.
Definition: btTransform.h:112
btScalar sideFrictionStiffness2
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations...
Definition: btIDebugDraw.h:29
btScalar m_maxSuspensionForce
Definition: btWheelInfo.h:72
const btVector3 & getCenterOfMassPosition() const
Definition: btRigidBody.h:354
The btRigidBody is the main class for rigid body objects.
Definition: btRigidBody.h:62
btScalar length() const
Return the length of the vector.
Definition: btVector3.h:263
btScalar m_wheelsDampingCompression
Definition: btWheelInfo.h:65
btScalar m_deltaRotation
Definition: btWheelInfo.h:70
void btSetMax(T &a, const T &b)
Definition: btMinMax.h:50
void updateWheelTransform(int wheelIndex, bool interpolatedTransform=true)
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
btVector3 m_wheelAxleCS
Definition: btWheelInfo.h:59
btRigidBody * getRigidBody()
btScalar m_rollInfluence
Definition: btWheelInfo.h:71
btScalar m_steeringValue
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition: btTransform.h:34
btScalar m_wheelsDampingRelaxation
Definition: btWheelInfo.h:66
void setMassProps(btScalar mass, const btVector3 &inertia)
int getNumWheels() const
virtual void * castRay(const btVector3 &from, const btVector3 &to, btVehicleRaycasterResult &result)=0
RaycastInfo m_raycastInfo
Definition: btWheelInfo.h:53
void resize(int newsize, const T &fillData=T())
void updateSuspension(btScalar deltaTime)
btScalar m_clippedInvContactDotSuspension
Definition: btWheelInfo.h:112
btScalar m_brake
Definition: btWheelInfo.h:76
btRaycastVehicle(const btVehicleTuning &tuning, btRigidBody *chassis, btVehicleRaycaster *raycaster)
btVehicleRaycaster is provides interface for between vehicle simulation and raycasting ...
btVector3 m_frictionDirectionWorld
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition: btMatrix3x3.h:48
btRigidBody * m_chassisBody
btMotionState * getMotionState()
Definition: btRigidBody.h:474
const btVector3 & getLinearVelocity() const
Definition: btRigidBody.h:362
void applyImpulse(const btVector3 &impulse, const btVector3 &rel_pos)
Definition: btRigidBody.h:334
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
Definition: btQuaternion.h:55
int getRightAxis() const
btAlignedObjectArray< btScalar > m_forwardImpulse
btScalar m_engineForce
Definition: btWheelInfo.h:74
btAlignedObjectArray< btVector3 > m_axle
void setBrake(btScalar brake, int wheelIndex)
virtual void updateFriction(btScalar timeStep)
btScalar calcRollingFriction(btWheelContactPoint &contactPoint, int numWheelsOnGround)
virtual void getWorldTransform(btTransform &worldTrans) const =0
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
btWheelInfo & addWheel(const btVector3 &connectionPointCS0, const btVector3 &wheelDirectionCS0, const btVector3 &wheelAxleCS, btScalar suspensionRestLength, btScalar wheelRadius, const btVehicleTuning &tuning, bool isFrontWheel)
btAlignedObjectArray< btVector3 > m_forwardWS
btScalar getSteeringValue(int wheel) const