I wanted to find out if anyone has had any issues with a character bouncing off terrain or another object? I have a character to stays put on the terrain but when I run into even a small hill in the terrain my character bounces back and up off the terrain and comes back down due to gravity. It almost acts like an inflated ball.
I set restitution, angular damping and linear damping to 0. I have played with the various settings, and my character seems to bounce. I am trying to make my character act like a real human in the real world -- where if I run in something even just walking, I really am not going to bounce unless I am running full force and even that will only be a little bounce back and not up.
Maybe if I could get some pointers on making my character collisions behave more human like. I haven't setup any true kinematics with moving limbs with joints (that is alot of work right now), I just have an animated mesh that is completely a rigid body. That brings me to my next question, should my character be a rigid body or a soft body? humans have soft tissue but with rigid skeletons. I want to get the settings right before I go ahead with limbs and joints and having arms and legs collide with my environment.
Character bouncing off terrain
-
SteveSegreto
- Posts: 32
- Joined: Sun Sep 12, 2010 10:25 am
Re: Character bouncing off terrain
Have you tried the btKinematicCharacterController - it's basically just a swept-capsule that moves when you tell it to.
-
Cryogenik28
- Posts: 9
- Joined: Sat Oct 23, 2010 12:18 am
Re: Character bouncing off terrain
Yes -- my character controller is based on the btKinematicCharacterController -- here it is if you want to look it over:
and I basically set my character up this way:
So is this a correct way to do this? or am I doing something wrong with the character controller and setting up a rigid body tied to my mesh? I know that the btKinematicCharacterController that comes with latest version of Bullet (I'm using 2.77) isn't complete -- but do I need to add settings and particular functions to my controller to make my character do what I want? or do I set other settings like I am doing?
mMainCharBody->setFriction( 0.8f );
mMainCharBody->setGravity(btVector3(0, -9.8 * 2, 0));//0, -9.8, 0
mMainCharBody->setHitFraction(0);//0.8
mMainCharBody->setRestitution(0);//Restitution is amount of bounce //0.6
The good thing is I was able to get some boxes setup and my character onto a terrain and have everything interacting, just not the way I expected.
Another interesting thing, I use btCollisionObject::CF_CHARACTER_OBJECT and the character falls onto the train because of gravity and it is behaving as mentioned. If I change it to - btCollisionObject::CF_KINEMATIC_OBJECT -- then no interaction and no forces affect it (such as gravity), it goes through every object. So since I set my character and ghost up the way I did then I guess it would make sense that the Kinematic setting wouldn't work, so I would need some direction on a proper kinematic setup.
Also do you know any good kenematic character code that would create limbs and joints ( or based on an animated mesh in ogre that has a skeleton, since I am using bullet with Ogre)?
Anyway, thanks for answering any and all of my questions, this would help me get alot farther now that I understand the basics of Bullet with my Ogre world.
Code: Select all
/**
* Orginal licence:
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef CHARACTERCONTROLLER
#define CHARACTERCONTROLLER
#include <LinearMath/btVector3.h>
#include <BulletDynamics/Character/btCharacterControllerInterface.h>
#include <BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h>
class btCollisionShape;
class btRigidBody;
class btCollisionWorld;
class btCollisionDispatcher;
class btPairCachingGhostObject;
class btConvexShape;
//---------------------------------------------------------------------------------------
///btKinematicCharacterController is an object that supports a sliding motion in a world.
///It uses a ghost object and convex sweep test to test for upcoming collisions. This is combined with discrete collision detection to recover from penetrations.
///Interaction between btKinematicCharacterController and dynamic rigid bodies needs to be explicity implemented by the user.
class CharacterController: public btCharacterControllerInterface
{
protected:
btScalar m_halfHeight;
btPairCachingGhostObject* m_ghostObject;
btConvexShape* m_convexShape;//is also in m_ghostObject, but it needs to be convex, so we store it here to avoid upcast
btScalar m_verticalVelocity;
btScalar m_verticalOffset;
btScalar m_fallSpeed;
btScalar m_jumpSpeed;
btScalar m_maxJumpHeight;
btScalar m_maxSlopeRadians; // Slope angle that is set (used for returning the exact value)
btScalar m_maxSlopeCosine; // Cosine equivalent of m_maxSlopeRadians (calculated once when set, for optimization)
btScalar m_gravity;
btScalar m_turnAngle;
btScalar m_maxSlopeAngle;
btScalar m_stepHeight;
btScalar m_addedMargin;//@todo: remove this and fix the code
///this is the desired walk direction, set by the user
btVector3 m_walkDirection;
btVector3 m_normalizedDirection;
//some internal variables
btVector3 m_currentPosition;
btScalar m_currentStepOffset;
btVector3 m_targetPosition;
///keep track of the contact manifolds
btManifoldArray m_manifoldArray;
bool m_touchingContact;
btVector3 m_touchingNormal;
bool m_wasOnGround;
bool m_wasJumping;
bool m_useGhostObjectSweepTest;
bool m_useWalkDirection;
btScalar m_velocityTimeInterval;
int m_upAxis;
static btVector3* getUpAxisDirections();
btVector3 computeReflectionDirection (const btVector3& direction, const btVector3& normal);
btVector3 parallelComponent (const btVector3& direction, const btVector3& normal);
btVector3 perpindicularComponent (const btVector3& direction, const btVector3& normal);
bool recoverFromPenetration ( btCollisionWorld* collisionWorld);
void stepUp (btCollisionWorld* collisionWorld);
void updateTargetPositionBasedOnCollision (const btVector3& hit_normal, btScalar tangentMag = btScalar(0.0), btScalar normalMag = btScalar(1.0));
void stepForwardAndStrafe (btCollisionWorld* collisionWorld, const btVector3& walkMove);
void stepDown (btCollisionWorld* collisionWorld, btScalar dt);
public:
CharacterController();
CharacterController(btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, int upAxis = 1);
~CharacterController();
///btActionInterface interface
virtual void updateAction( btCollisionWorld* collisionWorld,btScalar deltaTime)
{
preStep ( collisionWorld);
playerStep (collisionWorld, deltaTime);
}
///btActionInterface interface
void debugDraw(btIDebugDraw* debugDrawer);
void setUpAxis (int axis)
{
if (axis < 0)
axis = 0;
if (axis > 2)
axis = 2;
m_upAxis = axis;
}
/// This should probably be called setPositionIncrementPerSimulatorStep.
/// This is neither a direction nor a velocity, but the amount to
/// increment the position each simulation iteration, regardless
/// of dt.
/// This call will reset any velocity set by setVelocityForTimeInterval().
virtual void setWalkDirection(const btVector3& walkDirection);
/// Caller provides a velocity with which the character should move for
/// the given time period. After the time period, velocity is reset
/// to zero.
/// This call will reset any walk direction set by setWalkDirection().
/// Negative time intervals will result in no motion.
virtual void setVelocityForTimeInterval(const btVector3& velocity,
btScalar timeInterval);
void setTurnAngle(btScalar ang) { m_turnAngle = ang; };
void reset ();
void warp (const btVector3& origin);
void preStep ( btCollisionWorld* collisionWorld);
void playerStep ( btCollisionWorld* collisionWorld, btScalar dt);
void setFallSpeed (btScalar fallSpeed) { m_fallSpeed = btFabs(fallSpeed); }
void setJumpSpeed (btScalar jumpSpeed) { m_jumpSpeed = btFabs(jumpSpeed); }
void setMaxJumpHeight (btScalar maxJumpHeight) { m_maxJumpHeight = maxJumpHeight; }
///
bool isJumping ()const { return m_wasJumping; }
///
bool canJump() const { return onGround(); }
void jump(/*btCollisionWorld* cw, btScalar dt*/);
void setGravity(btScalar gravity) { m_gravity = gravity; }
btScalar getGravity() const { return m_gravity; }
/// The max slope determines the maximum angle that the controller can walk up.
/// The slope angle is measured in radians.
void setMaxSlope(btScalar slopeRadians) { m_maxSlopeRadians = slopeRadians; m_maxSlopeCosine = btCos(slopeRadians); }
btScalar getMaxSlope() const { return m_maxSlopeRadians; }
btPairCachingGhostObject* getGhostObject() { return m_ghostObject; }
void setUseGhostSweepTest(bool use) { m_useGhostObjectSweepTest = use; }
bool onGround() const { return m_verticalVelocity == 0.0 && m_verticalOffset == 0.0; }
};
#endif // CHARACTERCONTROLLERCode: Select all
/**
* Orginal licence:
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "CharacterController.h"
#include <LinearMath/btIDebugDraw.h>
#include <BulletCollision/CollisionDispatch/btGhostObject.h>
#include <BulletCollision/CollisionShapes/btMultiSphereShape.h>
#include <BulletCollision/BroadphaseCollision/btOverlappingPairCache.h>
#include <BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h>
#include <BulletCollision/CollisionDispatch/btCollisionWorld.h>
#include <LinearMath/btDefaultMotionState.h>
#include <iostream>
//---------------------------------------------------------------------------------------
// static helper method
static btVector3 getNormalizedVector(const btVector3& v)
{
btVector3 n = v.normalized();
if (n.length() < SIMD_EPSILON) {
n.setValue(0, 0, 0);
}
return n;
}
//---------------------------------------------------------------------------------------
///@todo Interact with dynamic objects,
///Ride kinematicly animated platforms properly
///More realistic (or maybe just a config option) falling
/// -> Should integrate falling velocity manually and use that in stepDown()
///Support jumping
///Support ducking
class btKinematicClosestNotMeRayResultCallback : public btCollisionWorld::ClosestRayResultCallback
{
public:
btKinematicClosestNotMeRayResultCallback (btCollisionObject* me) : btCollisionWorld::ClosestRayResultCallback(btVector3(0.0, 0.0, 0.0), btVector3(0.0, 0.0, 0.0))
{
m_me = me;
}
virtual btScalar addSingleResult(btCollisionWorld::LocalRayResult& rayResult,bool normalInWorldSpace)
{
if (rayResult.m_collisionObject == m_me)
return 1.0;
return ClosestRayResultCallback::addSingleResult (rayResult, normalInWorldSpace);
}
protected:
btCollisionObject* m_me;
};
//---------------------------------------------------------------------------------------
class btKinematicClosestNotMeConvexResultCallback : public btCollisionWorld::ClosestConvexResultCallback
{
public:
btKinematicClosestNotMeConvexResultCallback (btCollisionObject* me, const btVector3& up, btScalar minSlopeDot)
: btCollisionWorld::ClosestConvexResultCallback(btVector3(0.0, 0.0, 0.0), btVector3(0.0, 0.0, 0.0))
, m_me(me)
, m_up(up)
, m_minSlopeDot(minSlopeDot)
{
}
virtual btScalar addSingleResult(btCollisionWorld::LocalConvexResult& convexResult,bool normalInWorldSpace)
{
if (convexResult.m_hitCollisionObject == m_me)
return btScalar(1.0);
//for trigger filtering
if (!convexResult.m_hitCollisionObject->hasContactResponse())
return btScalar(1.0);
btVector3 hitNormalWorld;
if (normalInWorldSpace)
{
hitNormalWorld = convexResult.m_hitNormalLocal;
} else
{
///need to transform normal into worldspace
hitNormalWorld = convexResult.m_hitCollisionObject->getWorldTransform().getBasis()*convexResult.m_hitNormalLocal;
}
btScalar dotUp = m_up.dot(hitNormalWorld);
if (dotUp < m_minSlopeDot) {
return btScalar(1.0);
}
return ClosestConvexResultCallback::addSingleResult (convexResult, normalInWorldSpace);
}
protected:
btCollisionObject* m_me;
const btVector3 m_up;
btScalar m_minSlopeDot;
};
//---------------------------------------------------------------------------------------
/*
* Returns the reflection direction of a ray going 'direction' hitting a surface with normal 'normal'
*
* from: http://www-cs-students.stanford.edu/~adityagp/final/node3.html
*/
btVector3 CharacterController::computeReflectionDirection (const btVector3& direction, const btVector3& normal)
{
return direction - (btScalar(2.0) * direction.dot(normal)) * normal;
}
//---------------------------------------------------------------------------------------
/*
* Returns the portion of 'direction' that is parallel to 'normal'
*/
btVector3 CharacterController::parallelComponent (const btVector3& direction, const btVector3& normal)
{
btScalar magnitude = direction.dot(normal);
return normal * magnitude;
}
//---------------------------------------------------------------------------------------
/*
* Returns the portion of 'direction' that is perpindicular to 'normal'
*/
btVector3 CharacterController::perpindicularComponent (const btVector3& direction, const btVector3& normal)
{
return direction - parallelComponent(direction, normal);
}
//---------------------------------------------------------------------------------------
CharacterController::CharacterController ()
{
}
//---------------------------------------------------------------------------------------
CharacterController::CharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, int upAxis)
{
m_upAxis = upAxis;
m_addedMargin = 0.02f;
m_walkDirection.setValue(0,0,0);
m_useGhostObjectSweepTest = true;
m_ghostObject = ghostObject;
m_stepHeight = stepHeight;
m_turnAngle = btScalar(0.0);
m_convexShape=convexShape;
m_useWalkDirection = true; // use walk direction by default, legacy behavior
m_velocityTimeInterval = 0.0;
m_verticalVelocity = 0.0;
m_verticalOffset = 0.0;
m_gravity = 9.8f;//1G // * 3.0f ; // 3G acceleration.
m_fallSpeed = 55.0f; // Terminal velocity of a sky diver in m/s.
m_jumpSpeed = 10.0f; // ?
m_wasOnGround = false;
m_wasJumping = false;
setMaxSlope(btRadians(45.0f));
}
//---------------------------------------------------------------------------------------
CharacterController::~CharacterController ()
{
}
//---------------------------------------------------------------------------------------
bool CharacterController::recoverFromPenetration ( btCollisionWorld* collisionWorld)
{
bool penetration = false;
collisionWorld->getDispatcher()->dispatchAllCollisionPairs(m_ghostObject->getOverlappingPairCache(), collisionWorld->getDispatchInfo(), collisionWorld->getDispatcher());
m_currentPosition = m_ghostObject->getWorldTransform().getOrigin();
btScalar maxPen = btScalar(0.0);
for (int i = 0; i < m_ghostObject->getOverlappingPairCache()->getNumOverlappingPairs(); i++)
{
m_manifoldArray.resize(0);
btBroadphasePair* collisionPair = &m_ghostObject->getOverlappingPairCache()->getOverlappingPairArray()[i];
//for trigger filtering
if (!static_cast<btCollisionObject*>(collisionPair->m_pProxy0->m_clientObject)->hasContactResponse()
|| !static_cast<btCollisionObject*>(collisionPair->m_pProxy1->m_clientObject)->hasContactResponse())
continue;
if (collisionPair->m_algorithm)
collisionPair->m_algorithm->getAllContactManifolds(m_manifoldArray);
for (int j=0;j<m_manifoldArray.size();j++)
{
btPersistentManifold* manifold = m_manifoldArray[j];
btScalar directionSign = manifold->getBody0() == m_ghostObject ? btScalar(-1.0) : btScalar(1.0);
for (int p=0;p<manifold->getNumContacts();p++)
{
const btManifoldPoint&pt = manifold->getContactPoint(p);
btScalar dist = pt.getDistance();
if (dist < 0.0)
{
if (dist < maxPen)
{
maxPen = dist;
m_touchingNormal = pt.m_normalWorldOnB * directionSign;//??
}
m_currentPosition += pt.m_normalWorldOnB * directionSign * dist * btScalar(0.2);
penetration = true;
} else {
//printf("touching %f\n", dist);
}
}
//manifold->clearManifold();
}
}
btTransform newTrans = m_ghostObject->getWorldTransform();
newTrans.setOrigin(m_currentPosition);
m_ghostObject->setWorldTransform(newTrans);
// printf("m_touchingNormal = %f,%f,%f\n",m_touchingNormal[0],m_touchingNormal[1],m_touchingNormal[2]);
return penetration;
}
//---------------------------------------------------------------------------------------
void CharacterController::stepUp ( btCollisionWorld* world)
{
// phase 1: up
btTransform start, end;
m_targetPosition = m_currentPosition + getUpAxisDirections()[m_upAxis] * (m_stepHeight + (m_verticalOffset > 0.f?m_verticalOffset:0.f));
start.setIdentity ();
end.setIdentity ();
/* FIXME: Handle penetration properly */
start.setOrigin (m_currentPosition + getUpAxisDirections()[m_upAxis] * (m_convexShape->getMargin() + m_addedMargin));
end.setOrigin (m_targetPosition);
btKinematicClosestNotMeConvexResultCallback callback (m_ghostObject, -getUpAxisDirections()[m_upAxis], btScalar(0.7071));
callback.m_collisionFilterGroup = getGhostObject()->getBroadphaseHandle()->m_collisionFilterGroup;
callback.m_collisionFilterMask = getGhostObject()->getBroadphaseHandle()->m_collisionFilterMask;
if (m_useGhostObjectSweepTest)
{
m_ghostObject->convexSweepTest (m_convexShape, start, end, callback, world->getDispatchInfo().m_allowedCcdPenetration);
}
else
{
world->convexSweepTest (m_convexShape, start, end, callback);
}
if (callback.hasHit())
{
// Only modify the position if the hit was a slope and not a wall or ceiling.
if(callback.m_hitNormalWorld.dot(getUpAxisDirections()[m_upAxis]) > 0.0)
{
// we moved up only a fraction of the step height
m_currentStepOffset = m_stepHeight * callback.m_closestHitFraction;
m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, callback.m_closestHitFraction);
}
m_verticalVelocity = 0.0;
m_verticalOffset = 0.0;
} else {
m_currentStepOffset = m_stepHeight;
m_currentPosition = m_targetPosition;
}
}
//---------------------------------------------------------------------------------------
void CharacterController::updateTargetPositionBasedOnCollision (const btVector3& hitNormal, btScalar tangentMag, btScalar normalMag)
{
btVector3 movementDirection = m_targetPosition - m_currentPosition;
btScalar movementLength = movementDirection.length();
if (movementLength>SIMD_EPSILON)
{
movementDirection.normalize();
btVector3 reflectDir = computeReflectionDirection (movementDirection, hitNormal);
reflectDir.normalize();
btVector3 parallelDir, perpindicularDir;
parallelDir = parallelComponent (reflectDir, hitNormal);
perpindicularDir = perpindicularComponent (reflectDir, hitNormal);
m_targetPosition = m_currentPosition;
if (0)//tangentMag != 0.0)
{
btVector3 parComponent = parallelDir * btScalar (tangentMag*movementLength);
// printf("parComponent=%f,%f,%f\n",parComponent[0],parComponent[1],parComponent[2]);
m_targetPosition += parComponent;
}
if (normalMag != 0.0)
{
btVector3 perpComponent = perpindicularDir * btScalar (normalMag*movementLength);
// printf("perpComponent=%f,%f,%f\n",perpComponent[0],perpComponent[1],perpComponent[2]);
m_targetPosition += perpComponent;
}
} else
{
// printf("movementLength don't normalize a zero vector\n");
}
}
//---------------------------------------------------------------------------------------
void CharacterController::stepForwardAndStrafe ( btCollisionWorld* collisionWorld, const btVector3& walkMove)
{
// printf("m_normalizedDirection=%f,%f,%f\n",
// m_normalizedDirection[0],m_normalizedDirection[1],m_normalizedDirection[2]);
// phase 2: forward and strafe
btTransform start, end;
m_targetPosition = m_currentPosition + walkMove;
start.setIdentity ();
end.setIdentity ();
btScalar fraction = 1.0;
btScalar distance2 = (m_currentPosition-m_targetPosition).length2();
// printf("distance2=%f\n",distance2);
if (m_touchingContact)
{
if (m_normalizedDirection.dot(m_touchingNormal) > btScalar(0.0))
{
updateTargetPositionBasedOnCollision (m_touchingNormal);
}
}
int maxIter = 10;
while (fraction > btScalar(0.01) && maxIter-- > 0)
{
start.setOrigin (m_currentPosition);
end.setOrigin (m_targetPosition);
btVector3 sweepDirNegative(m_currentPosition - m_targetPosition);
btKinematicClosestNotMeConvexResultCallback callback (m_ghostObject, sweepDirNegative, btScalar(0.0));
callback.m_collisionFilterGroup = getGhostObject()->getBroadphaseHandle()->m_collisionFilterGroup;
callback.m_collisionFilterMask = getGhostObject()->getBroadphaseHandle()->m_collisionFilterMask;
btScalar margin = m_convexShape->getMargin();
m_convexShape->setMargin(margin + m_addedMargin);
if (m_useGhostObjectSweepTest)
{
m_ghostObject->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration);
} else
{
collisionWorld->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration);
}
m_convexShape->setMargin(margin);
fraction -= callback.m_closestHitFraction;
if (callback.hasHit())
{
// we moved only a fraction
btScalar hitDistance;
hitDistance = (callback.m_hitPointWorld - m_currentPosition).length();
// m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, callback.m_closestHitFraction);
updateTargetPositionBasedOnCollision (callback.m_hitNormalWorld);
btVector3 currentDir = m_targetPosition - m_currentPosition;
distance2 = currentDir.length2();
if (distance2 > SIMD_EPSILON)
{
currentDir.normalize();
/* See Quake2: "If velocity is against original velocity, stop ead to avoid tiny oscilations in sloping corners." */
if (currentDir.dot(m_normalizedDirection) <= btScalar(0.0))
{
break;
}
} else
{
// printf("currentDir: don't normalize a zero vector\n");
break;
}
} else {
// we moved whole way
m_currentPosition = m_targetPosition;
}
// if (callback.m_closestHitFraction == 0.f)
// break;
}
}
//---------------------------------------------------------------------------------------
void CharacterController::stepDown ( btCollisionWorld* collisionWorld, btScalar dt)
{
btTransform start, end;
// phase 3: down
/*btScalar additionalDownStep = (m_wasOnGround && !onGround()) ? m_stepHeight : 0.0;
btVector3 step_drop = getUpAxisDirections()[m_upAxis] * (m_currentStepOffset + additionalDownStep);
btScalar downVelocity = (additionalDownStep == 0.0 && m_verticalVelocity<0.0?-m_verticalVelocity:0.0) * dt;
btVector3 gravity_drop = getUpAxisDirections()[m_upAxis] * downVelocity;
m_targetPosition -= (step_drop + gravity_drop);*/
btScalar downVelocity = (m_verticalVelocity<0.f?-m_verticalVelocity:0.f) * dt;
if(downVelocity > 0.0// && downVelocity < m_stepHeight //TEST
&& (m_wasOnGround || !m_wasJumping))
{
//if (downVelocity < m_stepHeight) //TODO to jak do ziemi <m_stepHeight
// downVelocity = m_stepHeight;
////TEST for better falling
if(downVelocity > m_fallSpeed)
downVelocity = m_fallSpeed;
////TEST END
//downVelocity = m_stepHeight;
}
btVector3 step_drop = getUpAxisDirections()[m_upAxis] * (m_currentStepOffset + downVelocity);
m_targetPosition -= step_drop;
start.setIdentity ();
end.setIdentity ();
start.setOrigin (m_currentPosition);
end.setOrigin (m_targetPosition);
btKinematicClosestNotMeConvexResultCallback callback (m_ghostObject, getUpAxisDirections()[m_upAxis], m_maxSlopeCosine);
callback.m_collisionFilterGroup = getGhostObject()->getBroadphaseHandle()->m_collisionFilterGroup;
callback.m_collisionFilterMask = getGhostObject()->getBroadphaseHandle()->m_collisionFilterMask;
if (m_useGhostObjectSweepTest)
{
m_ghostObject->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration);
} else
{
collisionWorld->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration);
}
if (callback.hasHit())
{
// we dropped a fraction of the height -> hit floor
m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, callback.m_closestHitFraction);
m_verticalVelocity = 0.0;
m_verticalOffset = 0.0;
m_wasJumping = false;
} else {
// we dropped the full height
m_currentPosition = m_targetPosition;
}
}
//---------------------------------------------------------------------------------------
void CharacterController::setWalkDirection(const btVector3& walkDirection)
{
m_useWalkDirection = true;
m_walkDirection = walkDirection;
m_normalizedDirection = getNormalizedVector(m_walkDirection);
}
//---------------------------------------------------------------------------------------
void CharacterController::setVelocityForTimeInterval(const btVector3& velocity, btScalar timeInterval)
{
// printf("setVelocity!\n");
// printf(" interval: %f\n", timeInterval);
// printf(" velocity: (%f, %f, %f)\n",
// velocity.x(), velocity.y(), velocity.z());
m_useWalkDirection = false;
m_walkDirection = velocity;
m_normalizedDirection = getNormalizedVector(m_walkDirection);
m_velocityTimeInterval = timeInterval;
}
//---------------------------------------------------------------------------------------
void CharacterController::reset ()
{
}
//---------------------------------------------------------------------------------------
void CharacterController::warp (const btVector3& origin)
{
btTransform xform;
xform.setIdentity();
xform.setOrigin (origin);
m_ghostObject->setWorldTransform (xform);
}
//---------------------------------------------------------------------------------------
void CharacterController::preStep(btCollisionWorld* collisionWorld)
{
int numPenetrationLoops = 0;
m_touchingContact = false;
while (recoverFromPenetration (collisionWorld))
{
numPenetrationLoops++;
m_touchingContact = true;
if (numPenetrationLoops > 4)
{
//printf("character could not recover from penetration = %d\n", numPenetrationLoops);
break;
}
}
m_currentPosition = m_ghostObject->getWorldTransform().getOrigin();
m_targetPosition = m_currentPosition;
// printf("m_targetPosition=%f,%f,%f\n",m_targetPosition[0],m_targetPosition[1],m_targetPosition[2]);
}
//---------------------------------------------------------------------------------------
//#include <stdio.h>
void CharacterController::playerStep ( btCollisionWorld* collisionWorld, btScalar dt)
{
// printf("playerStep(): ");
// printf(" dt = %f", dt);
// quick check...
if (!m_useWalkDirection && m_velocityTimeInterval <= 0.0) {
// printf("\n");
return; // no motion
}
m_wasOnGround = onGround();
// Update fall velocity.
m_verticalVelocity -= m_gravity * dt;
if(m_verticalVelocity > 0.0 && m_verticalVelocity > m_jumpSpeed)
{
m_verticalVelocity = m_jumpSpeed;
}
if(m_verticalVelocity < 0.0 && btFabs(m_verticalVelocity) > m_fallSpeed)
{
m_verticalVelocity = -m_fallSpeed;
}
m_verticalOffset = m_verticalVelocity * dt;
btTransform xform;
xform = m_ghostObject->getWorldTransform ();
// printf("walkDirection(%f,%f,%f)\n",walkDirection[0],walkDirection[1],walkDirection[2]);
// printf("walkSpeed=%f\n",walkSpeed);
stepUp (collisionWorld);
if (m_useWalkDirection) {
stepForwardAndStrafe (collisionWorld, m_walkDirection);
} else {
//printf(" time: %f", m_velocityTimeInterval);
// still have some time left for moving!
btScalar dtMoving =
(dt < m_velocityTimeInterval) ? dt : m_velocityTimeInterval;
m_velocityTimeInterval -= dt;
// how far will we move while we are moving?
btVector3 move = m_walkDirection * dtMoving;
//printf(" dtMoving: %f", dtMoving);
// okay, step
stepForwardAndStrafe(collisionWorld, move);
}
stepDown (collisionWorld, dt);
// printf("\n");
xform.setOrigin (m_currentPosition);
m_ghostObject->setWorldTransform (xform);
}
//---------------------------------------------------------------------------------------
void CharacterController::jump (/*btCollisionWorld* cw, btScalar dt*/)
{
if (!canJump())
return;
m_verticalVelocity = m_jumpSpeed;
m_wasJumping = true;
////New Jump Code
//m_jumpTime += dt;
//btVector3 newPos;
//newPos = m_startJumpPosition +
//(m_velocityOnJumpStart + m_jumpStartVelocity)*m_jumpTime +
//(btVector3(0, m_fallAcceleration, 0)*m_jumpTime*m_jumpTime)/2f;
//m_targetPosition = newPos;
#if 0
currently no jumping.
btTransform xform;
m_rigidBody->getMotionState()->getWorldTransform (xform);
btVector3 up = xform.getBasis()[1];
up.normalize ();
btScalar magnitude = (btScalar(1.0)/m_rigidBody->getInvMass()) * btScalar(8.0);
m_rigidBody->applyCentralImpulse (up * magnitude);
#endif
}
//---------------------------------------------------------------------------------------
btVector3* CharacterController::getUpAxisDirections()
{
static btVector3 sUpAxisDirection[3] = { btVector3(1.0f, 0.0f, 0.0f), btVector3(0.0f, 1.0f, 0.0f), btVector3(0.0f, 0.0f, 1.0f) };
return sUpAxisDirection;
}
//---------------------------------------------------------------------------------------
void CharacterController::debugDraw(btIDebugDraw* debugDrawer)
{
debugDrawer;
}
//---------------------------------------------------------------------------------------
and I basically set my character up this way:
Code: Select all
//// Update owner entity's SceneNode
MainCharNode = mMainCharacter->getMainNode();
Ogre::Entity* mMainCharEntity = mMainCharacter->getMainEntity();
BtOgre::StaticMeshToShapeConverter converter(mMainCharEntity);
btConvexShape* mMainCharShape = converter.createConvex();
Ogre::Quaternion Q = MainCharNode->getOrientation();
Ogre::Vector3 vec3Pos2 = MainCharNode->getPosition();
//------------------------------ ghost ------------------------------
ghostShape = static_cast<btCollisionShape*>(mMainCharShape);
/// Create Dynamic Objects
ghostTransform.setIdentity();
ghostTransform.setRotation(btQuaternion(Q.x, Q.y, Q.z, Q.w));
vec3Pos2 = Ogre::Vector3(vec3Pos2.x, vec3Pos2.y, vec3Pos2.z);
ghostTransform.setOrigin(btVector3(vec3Pos2.x, vec3Pos2.y, vec3Pos2.z));//ghostTransform.setOrigin(btVector3(-900, 450, -1150));
m_charGhostObject = new btPairCachingGhostObject();
m_charGhostObject->setWorldTransform(ghostTransform);
btGhostPairCallback* ghostPairCallback = new btGhostPairCallback();
overlappingPairCache->getOverlappingPairCache()->setInternalGhostPairCallback(ghostPairCallback);
m_charGhostObject->setCollisionShape(ghostShape);
m_charGhostObject->setCollisionFlags(m_charGhostObject->getCollisionFlags() | btCollisionObject::CF_NO_CONTACT_RESPONSE);//CF_NO_CONTACT_RESPONSE
m_charGhostObject->setActivationState(DISABLE_DEACTIVATION);
collisionShapes.push_back(ghostShape);
// Debug Draw
mDebugDraw = new BtOgre::DebugDrawer(mSceneMgr->getRootSceneNode(), dynamicsWorld);
dynamicsWorld->setDebugDrawer(mDebugDraw);
//------------------------------ character ------------------------------
fallShape = static_cast<btCollisionShape*>(mMainCharShape);
fallShapeTransform.setIdentity();
vec3Pos2 = Ogre::Vector3(vec3Pos2.x, vec3Pos2.y, vec3Pos2.z);
fallShapeTransform.setOrigin(btVector3(vec3Pos2.x, vec3Pos2.y, vec3Pos2.z));//fallShapeTransform.setOrigin(btVector3(-950, 450, -1150));
fallShapeTransform.setRotation(btQuaternion(Q.x, Q.y, Q.z, Q.w));
btScalar mass(50.0f);//50.0f kilos //1.0f
btVector3 fallInertia(0,0,-1.0);
fallShape->calculateLocalInertia(mass, fallInertia);
fallMotionState = new BtOgre::RigidBodyState(MainCharNode);
btRigidBody::btRigidBodyConstructionInfo fallRigidBodyCI(mass, fallMotionState, fallShape, fallInertia);
mMainCharBody = new btRigidBody(fallRigidBodyCI);
mMainCharBody->setUserPointer(MainCharNode); //MainCharNode//(void*)1
collisionShapes.push_back(fallShape);
mMainCharBody->setFriction(0.8);
mMainCharBody->setGravity(btVector3(0, -9.8 * 2, 0));//0, -9.8, 0
mMainCharBody->setHitFraction(0);//0.8
mMainCharBody->setRestitution(0);//Restitution is amount of bounce //0.6
mMainCharBody->setCollisionFlags(mMainCharBody->getCollisionFlags() | btCollisionObject::CF_CHARACTER_OBJECT);//CF_CHARACTER_OBJECT
mMainCharBody->setCollisionFlags(mMainCharBody->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
mMainCharBody->getWorldTransform().setOrigin(btVector3(vec3Pos2.x, vec3Pos2.y, vec3Pos2.z));
mMainCharBody->getWorldTransform().setRotation(btQuaternion(Q.x, Q.y, Q.z, Q.w));
//Set Main Character variables for moving
mMainCharacter->moveTransform = fallShapeTransform;
mMainCharacter->moveBody = mMainCharBody;
btScalar stepHeight = 0.35f; //0.5f
m_character = new CharacterController(m_charGhostObject, static_cast<btConvexShape*>(fallShape), stepHeight);
//The max slope angle a character can walk up
m_character->setMaxSlope(btScalar(45.0*SIMD_RADS_PER_DEG));//45.0*SIMD_RADS_PER_DEG
m_character->preStep(dynamicsWorld);
m_character->setGravity(-9.8 * 2);
m_character->setUseGhostSweepTest(true);
m_character->setUpAxis(2);
//------------------------------ Setup ghost and character to dynamics world ------------------------------
//only collide with static for now (no interaction with dynamic objects)
//dynamicsWorld->addCollisionObject(actorGhost, btBroadphaseProxy::CharacterFilter, btBroadphaseProxy::StaticFilter|btBroadphaseProxy::DefaultFilter);//btBroadphaseProxy::CharacterFilter, btBroadphaseProxy::AllFilter);//btBroadphaseProxy::StaticFilter|btBroadphaseProxy::DefaultFilter); //btBroadphaseProxy::AllFilter);
dynamicsWorld->addCollisionObject(m_charGhostObject, btBroadphaseProxy::CharacterFilter, btBroadphaseProxy::StaticFilter|btBroadphaseProxy::DefaultFilter);//btBroadphaseProxy::CharacterFilter, btBroadphaseProxy::AllFilter);//btBroadphaseProxy::StaticFilter|btBroadphaseProxy::DefaultFilter); //btBroadphaseProxy::AllFilter);
dynamicsWorld->addAction(m_character);
dynamicsWorld->addRigidBody(mMainCharBody);
dynamicsWorld->addCollisionObject(m_charGhostObject, btBroadphaseProxy::CharacterFilter, btBroadphaseProxy::StaticFilter | btBroadphaseProxy::AllFilter);//btBroadphaseProxy::CharacterFilter, btBroadphaseProxy::AllFilter);//btBroadphaseProxy::StaticFilter|btBroadphaseProxy::DefaultFilter); //btBroadphaseProxy::AllFilter);
mMainCharBody->setFriction( 0.8f );
mMainCharBody->setGravity(btVector3(0, -9.8 * 2, 0));//0, -9.8, 0
mMainCharBody->setHitFraction(0);//0.8
mMainCharBody->setRestitution(0);//Restitution is amount of bounce //0.6
The good thing is I was able to get some boxes setup and my character onto a terrain and have everything interacting, just not the way I expected.
Another interesting thing, I use btCollisionObject::CF_CHARACTER_OBJECT and the character falls onto the train because of gravity and it is behaving as mentioned. If I change it to - btCollisionObject::CF_KINEMATIC_OBJECT -- then no interaction and no forces affect it (such as gravity), it goes through every object. So since I set my character and ghost up the way I did then I guess it would make sense that the Kinematic setting wouldn't work, so I would need some direction on a proper kinematic setup.
Also do you know any good kenematic character code that would create limbs and joints ( or based on an animated mesh in ogre that has a skeleton, since I am using bullet with Ogre)?
Anyway, thanks for answering any and all of my questions, this would help me get alot farther now that I understand the basics of Bullet with my Ogre world.
Last edited by Cryogenik28 on Tue Oct 26, 2010 4:08 pm, edited 1 time in total.
-
Cryogenik28
- Posts: 9
- Joined: Sat Oct 23, 2010 12:18 am
Re: Character bouncing off terrain
I have played with hit-fraction, damping, restitution, etc. and I do get varying results -- but too much damping and I get a major slow down. I am sure playing with these things is only part of the story. A lot of what I have done was just put pieces together from the demos and this forum (as well as on the ogre forum), so I am sure it isn't complete, so all of those looking at this thread feel free to use my code and maybe we can all come to a legitimate answer. But it sure would be nice to know what hit-fraction really means, or restitution -- the code isn't commented well enough to make a proper determination. I know that the Bullet Physics creators and maintainers peruse this forum, can they answer what would be the best combination of settings and what would be best for a kinematic character. Because what is well documented is that the kinematic character controller isn't complete.
-
Cryogenik28
- Posts: 9
- Joined: Sat Oct 23, 2010 12:18 am
Re: Character bouncing off terrain
*Bump*
any ideas?
any ideas?