btKinematicCharacterController.h
Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2008 Erwin Coumans  http://bulletphysics.com
00004 
00005 This software is provided 'as-is', without any express or implied warranty.
00006 In no event will the authors be held liable for any damages arising from the use of this software.
00007 Permission is granted to anyone to use this software for any purpose, 
00008 including commercial applications, and to alter it and redistribute it freely, 
00009 subject to the following restrictions:
00010 
00011 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.
00012 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00013 3. This notice may not be removed or altered from any source distribution.
00014 */
00015 
00016 
00017 #ifndef BT_KINEMATIC_CHARACTER_CONTROLLER_H
00018 #define BT_KINEMATIC_CHARACTER_CONTROLLER_H
00019 
00020 #include "LinearMath/btVector3.h"
00021 
00022 #include "btCharacterControllerInterface.h"
00023 
00024 #include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h"
00025 
00026 
00027 class btCollisionShape;
00028 class btRigidBody;
00029 class btCollisionWorld;
00030 class btCollisionDispatcher;
00031 class btPairCachingGhostObject;
00032 
00036 class btKinematicCharacterController : public btCharacterControllerInterface
00037 {
00038 protected:
00039 
00040         btScalar m_halfHeight;
00041         
00042         btPairCachingGhostObject* m_ghostObject;
00043         btConvexShape*  m_convexShape;//is also in m_ghostObject, but it needs to be convex, so we store it here to avoid upcast
00044         
00045         btScalar m_verticalVelocity;
00046         btScalar m_verticalOffset;
00047         btScalar m_fallSpeed;
00048         btScalar m_jumpSpeed;
00049         btScalar m_maxJumpHeight;
00050         btScalar m_maxSlopeRadians; // Slope angle that is set (used for returning the exact value)
00051         btScalar m_maxSlopeCosine;  // Cosine equivalent of m_maxSlopeRadians (calculated once when set, for optimization)
00052         btScalar m_gravity;
00053 
00054         btScalar m_turnAngle;
00055         
00056         btScalar m_stepHeight;
00057 
00058         btScalar        m_addedMargin;//@todo: remove this and fix the code
00059 
00061         btVector3       m_walkDirection;
00062         btVector3       m_normalizedDirection;
00063 
00064         //some internal variables
00065         btVector3 m_currentPosition;
00066         btScalar  m_currentStepOffset;
00067         btVector3 m_targetPosition;
00068 
00070         btManifoldArray m_manifoldArray;
00071 
00072         bool m_touchingContact;
00073         btVector3 m_touchingNormal;
00074 
00075         bool  m_wasOnGround;
00076         bool  m_wasJumping;
00077         bool    m_useGhostObjectSweepTest;
00078         bool    m_useWalkDirection;
00079         btScalar        m_velocityTimeInterval;
00080         int m_upAxis;
00081 
00082         static btVector3* getUpAxisDirections();
00083 
00084         btVector3 computeReflectionDirection (const btVector3& direction, const btVector3& normal);
00085         btVector3 parallelComponent (const btVector3& direction, const btVector3& normal);
00086         btVector3 perpindicularComponent (const btVector3& direction, const btVector3& normal);
00087 
00088         bool recoverFromPenetration ( btCollisionWorld* collisionWorld);
00089         void stepUp (btCollisionWorld* collisionWorld);
00090         void updateTargetPositionBasedOnCollision (const btVector3& hit_normal, btScalar tangentMag = btScalar(0.0), btScalar normalMag = btScalar(1.0));
00091         void stepForwardAndStrafe (btCollisionWorld* collisionWorld, const btVector3& walkMove);
00092         void stepDown (btCollisionWorld* collisionWorld, btScalar dt);
00093 public:
00094         btKinematicCharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, int upAxis = 1);
00095         ~btKinematicCharacterController ();
00096         
00097 
00099         virtual void updateAction( btCollisionWorld* collisionWorld,btScalar deltaTime)
00100         {
00101                 preStep ( collisionWorld);
00102                 playerStep (collisionWorld, deltaTime);
00103         }
00104         
00106         void    debugDraw(btIDebugDraw* debugDrawer);
00107 
00108         void setUpAxis (int axis)
00109         {
00110                 if (axis < 0)
00111                         axis = 0;
00112                 if (axis > 2)
00113                         axis = 2;
00114                 m_upAxis = axis;
00115         }
00116 
00122         virtual void    setWalkDirection(const btVector3& walkDirection);
00123 
00129         virtual void setVelocityForTimeInterval(const btVector3& velocity,
00130                                 btScalar timeInterval);
00131 
00132         void reset ();
00133         void warp (const btVector3& origin);
00134 
00135         void preStep (  btCollisionWorld* collisionWorld);
00136         void playerStep ( btCollisionWorld* collisionWorld, btScalar dt);
00137 
00138         void setFallSpeed (btScalar fallSpeed);
00139         void setJumpSpeed (btScalar jumpSpeed);
00140         void setMaxJumpHeight (btScalar maxJumpHeight);
00141         bool canJump () const;
00142 
00143         void jump ();
00144 
00145         void setGravity(btScalar gravity);
00146         btScalar getGravity() const;
00147 
00150         void setMaxSlope(btScalar slopeRadians);
00151         btScalar getMaxSlope() const;
00152 
00153         btPairCachingGhostObject* getGhostObject();
00154         void    setUseGhostSweepTest(bool useGhostObjectSweepTest)
00155         {
00156                 m_useGhostObjectSweepTest = useGhostObjectSweepTest;
00157         }
00158 
00159         bool onGround () const;
00160 };
00161 
00162 #endif // BT_KINEMATIC_CHARACTER_CONTROLLER_H
 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