btRaycastVehicle.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/
00003  *
00004  * Permission to use, copy, modify, distribute and sell this software
00005  * and its documentation for any purpose is hereby granted without fee,
00006  * provided that the above copyright notice appear in all copies.
00007  * Erwin Coumans makes no representations about the suitability 
00008  * of this software for any purpose.  
00009  * It is provided "as is" without express or implied warranty.
00010 */
00011 #ifndef BT_RAYCASTVEHICLE_H
00012 #define BT_RAYCASTVEHICLE_H
00013 
00014 #include "BulletDynamics/Dynamics/btRigidBody.h"
00015 #include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
00016 #include "btVehicleRaycaster.h"
00017 class btDynamicsWorld;
00018 #include "LinearMath/btAlignedObjectArray.h"
00019 #include "btWheelInfo.h"
00020 #include "BulletDynamics/Dynamics/btActionInterface.h"
00021 
00022 class btVehicleTuning;
00023 
00025 class btRaycastVehicle : public btActionInterface
00026 {
00027 
00028                 btAlignedObjectArray<btVector3> m_forwardWS;
00029                 btAlignedObjectArray<btVector3> m_axle;
00030                 btAlignedObjectArray<btScalar>  m_forwardImpulse;
00031                 btAlignedObjectArray<btScalar>  m_sideImpulse;
00032         
00034                 int     m_userConstraintType;
00035                 int     m_userConstraintId;
00036 
00037 public:
00038         class btVehicleTuning
00039                 {
00040                         public:
00041 
00042                         btVehicleTuning()
00043                                 :m_suspensionStiffness(btScalar(5.88)),
00044                                 m_suspensionCompression(btScalar(0.83)),
00045                                 m_suspensionDamping(btScalar(0.88)),
00046                                 m_maxSuspensionTravelCm(btScalar(500.)),
00047                                 m_frictionSlip(btScalar(10.5)),
00048                                 m_maxSuspensionForce(btScalar(6000.))
00049                         {
00050                         }
00051                         btScalar        m_suspensionStiffness;
00052                         btScalar        m_suspensionCompression;
00053                         btScalar        m_suspensionDamping;
00054                         btScalar        m_maxSuspensionTravelCm;
00055                         btScalar        m_frictionSlip;
00056                         btScalar        m_maxSuspensionForce;
00057 
00058                 };
00059 private:
00060 
00061         btScalar        m_tau;
00062         btScalar        m_damping;
00063         btVehicleRaycaster*     m_vehicleRaycaster;
00064         btScalar                m_pitchControl;
00065         btScalar        m_steeringValue; 
00066         btScalar m_currentVehicleSpeedKmHour;
00067 
00068         btRigidBody* m_chassisBody;
00069 
00070         int m_indexRightAxis;
00071         int m_indexUpAxis;
00072         int     m_indexForwardAxis;
00073 
00074         void defaultInit(const btVehicleTuning& tuning);
00075 
00076 public:
00077 
00078         //constructor to create a car from an existing rigidbody
00079         btRaycastVehicle(const btVehicleTuning& tuning,btRigidBody* chassis,    btVehicleRaycaster* raycaster );
00080 
00081         virtual ~btRaycastVehicle() ;
00082 
00083 
00085         virtual void updateAction( btCollisionWorld* collisionWorld, btScalar step)
00086         {
00087         (void) collisionWorld;
00088                 updateVehicle(step);
00089         }
00090         
00091 
00093         void    debugDraw(btIDebugDraw* debugDrawer);
00094                         
00095         const btTransform& getChassisWorldTransform() const;
00096         
00097         btScalar rayCast(btWheelInfo& wheel);
00098 
00099         virtual void updateVehicle(btScalar step);
00100         
00101         
00102         void resetSuspension();
00103 
00104         btScalar        getSteeringValue(int wheel) const;
00105 
00106         void    setSteeringValue(btScalar steering,int wheel);
00107 
00108 
00109         void    applyEngineForce(btScalar force, int wheel);
00110 
00111         const btTransform&      getWheelTransformWS( int wheelIndex ) const;
00112 
00113         void    updateWheelTransform( int wheelIndex, bool interpolatedTransform = true );
00114         
00115 //      void    setRaycastWheelInfo( int wheelIndex , bool isInContact, const btVector3& hitPoint, const btVector3& hitNormal,btScalar depth);
00116 
00117         btWheelInfo&    addWheel( const btVector3& connectionPointCS0, const btVector3& wheelDirectionCS0,const btVector3& wheelAxleCS,btScalar suspensionRestLength,btScalar wheelRadius,const btVehicleTuning& tuning, bool isFrontWheel);
00118 
00119         inline int              getNumWheels() const {
00120                 return int (m_wheelInfo.size());
00121         }
00122         
00123         btAlignedObjectArray<btWheelInfo>       m_wheelInfo;
00124 
00125 
00126         const btWheelInfo&      getWheelInfo(int index) const;
00127 
00128         btWheelInfo&    getWheelInfo(int index);
00129 
00130         void    updateWheelTransformsWS(btWheelInfo& wheel , bool interpolatedTransform = true);
00131 
00132         
00133         void setBrake(btScalar brake,int wheelIndex);
00134 
00135         void    setPitchControl(btScalar pitch)
00136         {
00137                 m_pitchControl = pitch;
00138         }
00139         
00140         void    updateSuspension(btScalar deltaTime);
00141 
00142         virtual void    updateFriction(btScalar timeStep);
00143 
00144 
00145 
00146         inline btRigidBody* getRigidBody()
00147         {
00148                 return m_chassisBody;
00149         }
00150 
00151         const btRigidBody* getRigidBody() const
00152         {
00153                 return m_chassisBody;
00154         }
00155 
00156         inline int      getRightAxis() const
00157         {
00158                 return m_indexRightAxis;
00159         }
00160         inline int getUpAxis() const
00161         {
00162                 return m_indexUpAxis;
00163         }
00164 
00165         inline int getForwardAxis() const
00166         {
00167                 return m_indexForwardAxis;
00168         }
00169 
00170         
00172         btVector3 getForwardVector() const
00173         {
00174                 const btTransform& chassisTrans = getChassisWorldTransform(); 
00175 
00176                 btVector3 forwardW ( 
00177                           chassisTrans.getBasis()[0][m_indexForwardAxis], 
00178                           chassisTrans.getBasis()[1][m_indexForwardAxis], 
00179                           chassisTrans.getBasis()[2][m_indexForwardAxis]); 
00180 
00181                 return forwardW;
00182         }
00183 
00185         btScalar        getCurrentSpeedKmHour() const
00186         {
00187                 return m_currentVehicleSpeedKmHour;
00188         }
00189 
00190         virtual void    setCoordinateSystem(int rightIndex,int upIndex,int forwardIndex)
00191         {
00192                 m_indexRightAxis = rightIndex;
00193                 m_indexUpAxis = upIndex;
00194                 m_indexForwardAxis = forwardIndex;
00195         }
00196 
00197 
00199         int getUserConstraintType() const
00200         {
00201                 return m_userConstraintType ;
00202         }
00203 
00204         void    setUserConstraintType(int userConstraintType)
00205         {
00206                 m_userConstraintType = userConstraintType;
00207         };
00208 
00209         void    setUserConstraintId(int uid)
00210         {
00211                 m_userConstraintId = uid;
00212         }
00213 
00214         int getUserConstraintId() const
00215         {
00216                 return m_userConstraintId;
00217         }
00218 
00219 };
00220 
00221 class btDefaultVehicleRaycaster : public btVehicleRaycaster
00222 {
00223         btDynamicsWorld*        m_dynamicsWorld;
00224 public:
00225         btDefaultVehicleRaycaster(btDynamicsWorld* world)
00226                 :m_dynamicsWorld(world)
00227         {
00228         }
00229 
00230         virtual void* castRay(const btVector3& from,const btVector3& to, btVehicleRaycasterResult& result);
00231 
00232 };
00233 
00234 
00235 #endif //BT_RAYCASTVEHICLE_H
00236 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31