Improved physics: karts are now less likely to lose contact

with the ground (and as a result start rotating on the spot).


git-svn-id: svn+ssh://svn.code.sf.net/p/supertuxkart/code/trunk/supertuxkart@2342 178a84e3-b1eb-0310-8ba1-8eac791a3b58
This commit is contained in:
hikerstk 2008-10-16 00:20:49 +00:00
parent 41ca66fc34
commit b1cb705777
17 changed files with 627 additions and 59 deletions

View File

@ -80,7 +80,7 @@
(front-wheel-connection 0.38 0.6 0)
(rear-wheel-connection 0.38 -0.6 0)
(suspension-rest 0.2 )
(suspension-travel-cm 500 )
(suspension-travel-cm 19 )
;; The z-axis velocity set when a jump is initiated. This will cause the
;; kart to start rising, till it is pulled back by gravity. A higher value
@ -98,6 +98,7 @@
(gear-power-increase 2.2 1.7 1.3)
(upright-tolerance 0.2)
(upright-max-force 30)
(track-connection-force 2)
(camera-max-accel 10)
(camera-max-brake 10)
(camera-distance 3.5)

View File

@ -0,0 +1,473 @@
/*
* Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/
*
* Permission to use, copy, modify, distribute and sell this software
* and its documentation for any purpose is hereby granted without fee,
* provided that the above copyright notice appear in all copies.
* Erwin Coumans makes no representations about the suitability
* of this software for any purpose.
* It is provided "as is" without express or implied warranty.
*/
#include "LinearMath/btVector3.h"
#include "btKart.h"
#include "BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h"
#include "BulletDynamics/ConstraintSolver/btJacobianEntry.h"
#include "LinearMath/btQuaternion.h"
#include "BulletDynamics/Dynamics/btDynamicsWorld.h"
#include "btVehicleRaycaster.h"
#include "btWheelInfo.h"
#include "LinearMath/btMinMax.h"
#include "BulletDynamics/ConstraintSolver/btContactConstraint.h"
struct btWheelContactPoint;
btScalar calcRollingFriction(btWheelContactPoint& contactPoint);
static btRigidBody s_fixedObject( 0,0,0);
btKart::btKart(const btVehicleTuning& tuning,btRigidBody* chassis, btVehicleRaycaster* raycaster )
: btRaycastVehicle(tuning, chassis, raycaster)
{
}
// ----------------------------------------------------------------------------
btKart::~btKart()
{
}
// ----------------------------------------------------------------------------
btScalar btKart::rayCast(btWheelInfo& wheel)
{
updateWheelTransformsWS( wheel,false);
btScalar depth = -1;
btScalar raylen = wheel.getSuspensionRestLength()+wheel.m_wheelsRadius;
btVector3 rayvector = wheel.m_raycastInfo.m_wheelDirectionWS * (raylen);
const btVector3& source = wheel.m_raycastInfo.m_hardPointWS;
wheel.m_raycastInfo.m_contactPointWS = source + rayvector;
const btVector3& target = wheel.m_raycastInfo.m_contactPointWS;
btScalar param = btScalar(0.);
btVehicleRaycaster::btVehicleRaycasterResult rayResults;
assert(m_vehicleRaycaster);
void* object = m_vehicleRaycaster->castRay(source,target,rayResults);
wheel.m_raycastInfo.m_groundObject = 0;
if (object)
{
param = rayResults.m_distFraction;
depth = raylen * rayResults.m_distFraction;
wheel.m_raycastInfo.m_contactNormalWS = rayResults.m_hitNormalInWorld;
wheel.m_raycastInfo.m_isInContact = true;
wheel.m_raycastInfo.m_groundObject = &s_fixedObject;//todo for driving on dynamic/movable objects!;
//wheel.m_raycastInfo.m_groundObject = object;
btScalar hitDistance = param*raylen;
wheel.m_raycastInfo.m_suspensionLength = hitDistance - wheel.m_wheelsRadius;
//clamp on max suspension travel
btScalar minSuspensionLength = wheel.getSuspensionRestLength() - wheel.m_maxSuspensionTravelCm*btScalar(0.01);
btScalar maxSuspensionLength = wheel.getSuspensionRestLength()+ wheel.m_maxSuspensionTravelCm*btScalar(0.01);
if (wheel.m_raycastInfo.m_suspensionLength < minSuspensionLength)
{
wheel.m_raycastInfo.m_suspensionLength = minSuspensionLength;
}
if (wheel.m_raycastInfo.m_suspensionLength > maxSuspensionLength)
{
wheel.m_raycastInfo.m_suspensionLength = maxSuspensionLength;
}
wheel.m_raycastInfo.m_contactPointWS = rayResults.m_hitPointInWorld;
btScalar denominator= wheel.m_raycastInfo.m_contactNormalWS.dot( wheel.m_raycastInfo.m_wheelDirectionWS );
btVector3 chassis_velocity_at_contactPoint;
btVector3 relpos = wheel.m_raycastInfo.m_contactPointWS-getRigidBody()->getCenterOfMassPosition();
chassis_velocity_at_contactPoint = getRigidBody()->getVelocityInLocalPoint(relpos);
btScalar projVel = wheel.m_raycastInfo.m_contactNormalWS.dot( chassis_velocity_at_contactPoint );
if ( denominator >= btScalar(-0.1))
{
wheel.m_suspensionRelativeVelocity = btScalar(0.0);
wheel.m_clippedInvContactDotSuspension = btScalar(1.0) / btScalar(0.1);
}
else
{
btScalar inv = btScalar(-1.) / denominator;
wheel.m_suspensionRelativeVelocity = projVel * inv;
wheel.m_clippedInvContactDotSuspension = inv;
}
} else
{
//put wheel info as in rest position
wheel.m_raycastInfo.m_suspensionLength = wheel.getSuspensionRestLength();
wheel.m_suspensionRelativeVelocity = btScalar(0.0);
wheel.m_raycastInfo.m_contactNormalWS = - wheel.m_raycastInfo.m_wheelDirectionWS;
wheel.m_clippedInvContactDotSuspension = btScalar(1.0);
}
return depth;
}
// ----------------------------------------------------------------------------
void btKart::updateVehicle( btScalar step )
{
{
for (int i=0;i<getNumWheels();i++)
{
updateWheelTransform(i,false);
}
}
m_currentVehicleSpeedKmHour = btScalar(3.6) * getRigidBody()->getLinearVelocity().length();
const btTransform& chassisTrans = getChassisWorldTransform();
btVector3 forwardW (
chassisTrans.getBasis()[0][m_indexForwardAxis],
chassisTrans.getBasis()[1][m_indexForwardAxis],
chassisTrans.getBasis()[2][m_indexForwardAxis]);
if (forwardW.dot(getRigidBody()->getLinearVelocity()) < btScalar(0.))
{
m_currentVehicleSpeedKmHour *= btScalar(-1.);
}
//
// simulate suspension
//
int i=0;
for (i=0;i<m_wheelInfo.size();i++)
{
btScalar depth;
depth = rayCast( m_wheelInfo[i]);
}
updateSuspension(step);
// A very unphysical thing to handle slopes that are a bit too steep
// or uneven (resulting in only one wheel on the ground)
// If only the front or only the rear wheels are on the ground, add
// a force pulling the axis down (towards the ground). Note that it
// is already guaranteed that either both or no wheels on one axis
// are on the ground, so we have to test only one of the wheels
for(int i=0; i<m_wheelInfo.size(); i++)
{
if(!(m_wheelInfo[i].m_raycastInfo.m_isInContact) )
{
btScalar mass=1.0f/m_chassisBody->getInvMass();
m_wheelInfo[i].m_wheelsSuspensionForce = -2.0f*mass;
}
}
for (i=0;i<m_wheelInfo.size();i++)
{
//apply suspension force
btWheelInfo& wheel = m_wheelInfo[i];
btScalar suspensionForce = wheel.m_wheelsSuspensionForce;
btScalar gMaxSuspensionForce = btScalar(6000.);
if (suspensionForce > gMaxSuspensionForce)
{
suspensionForce = gMaxSuspensionForce;
}
btVector3 impulse = wheel.m_raycastInfo.m_contactNormalWS * suspensionForce * step;
btVector3 relpos = wheel.m_raycastInfo.m_contactPointWS - getRigidBody()->getCenterOfMassPosition();
getRigidBody()->applyImpulse(impulse, relpos);
}
updateFriction( step);
for (i=0;i<m_wheelInfo.size();i++)
{
btWheelInfo& wheel = m_wheelInfo[i];
btVector3 relpos = wheel.m_raycastInfo.m_hardPointWS - getRigidBody()->getCenterOfMassPosition();
btVector3 vel = getRigidBody()->getVelocityInLocalPoint( relpos );
if (wheel.m_raycastInfo.m_isInContact)
{
const btTransform& chassisWorldTransform = getChassisWorldTransform();
btVector3 fwd (
chassisWorldTransform.getBasis()[0][m_indexForwardAxis],
chassisWorldTransform.getBasis()[1][m_indexForwardAxis],
chassisWorldTransform.getBasis()[2][m_indexForwardAxis]);
btScalar proj = fwd.dot(wheel.m_raycastInfo.m_contactNormalWS);
fwd -= wheel.m_raycastInfo.m_contactNormalWS * proj;
btScalar proj2 = fwd.dot(vel);
wheel.m_deltaRotation = (proj2 * step) / (wheel.m_wheelsRadius);
wheel.m_rotation += wheel.m_deltaRotation;
} else
{
wheel.m_rotation += wheel.m_deltaRotation;
}
wheel.m_deltaRotation *= btScalar(0.99);//damping of rotation when not in contact
}
}
// ----------------------------------------------------------------------------
void btKart::updateSuspension(btScalar deltaTime)
{
(void)deltaTime;
btScalar chassisMass = btScalar(1.) / m_chassisBody->getInvMass();
for (int w_it=0; w_it<getNumWheels(); w_it++)
{
btWheelInfo &wheel_info = m_wheelInfo[w_it];
if ( wheel_info.m_raycastInfo.m_isInContact )
{
btScalar force;
// Spring
{
btScalar susp_length = wheel_info.getSuspensionRestLength();
btScalar current_length = wheel_info.m_raycastInfo.m_suspensionLength;
btScalar length_diff = (susp_length - current_length);
force = wheel_info.m_suspensionStiffness
* length_diff * wheel_info.m_clippedInvContactDotSuspension;
}
// Damper
{
btScalar projected_rel_vel = wheel_info.m_suspensionRelativeVelocity;
{
btScalar susp_damping;
if ( projected_rel_vel < btScalar(0.0) )
{
susp_damping = wheel_info.m_wheelsDampingCompression;
}
else
{
susp_damping = wheel_info.m_wheelsDampingRelaxation;
}
force -= susp_damping * projected_rel_vel;
}
}
// RESULT
wheel_info.m_wheelsSuspensionForce = force * chassisMass;
if (wheel_info.m_wheelsSuspensionForce < btScalar(0.))
{
wheel_info.m_wheelsSuspensionForce = btScalar(0.);
}
}
else
{
wheel_info.m_wheelsSuspensionForce = btScalar(0.0);
}
} // for w_it<number of wheels
}
// ----------------------------------------------------------------------------
// FIXME: This structure has to be the same as the one declared in btRaycastVehicle.
// Unfortunately bullet (atm) does not declare this struct in the header file.
struct btWheelContactPoint
{
btRigidBody* m_body0;
btRigidBody* m_body1;
btVector3 m_frictionPositionWorld;
btVector3 m_frictionDirectionWorld;
btScalar m_jacDiagABInv;
btScalar m_maxImpulse;
btWheelContactPoint(btRigidBody* body0,btRigidBody* body1,const btVector3& frictionPosWorld,const btVector3& frictionDirectionWorld, btScalar maxImpulse)
:m_body0(body0),
m_body1(body1),
m_frictionPositionWorld(frictionPosWorld),
m_frictionDirectionWorld(frictionDirectionWorld),
m_maxImpulse(maxImpulse)
{
btScalar denom0 = body0->computeImpulseDenominator(frictionPosWorld,frictionDirectionWorld);
btScalar denom1 = body1->computeImpulseDenominator(frictionPosWorld,frictionDirectionWorld);
btScalar relaxation = 1.f;
m_jacDiagABInv = relaxation/(denom0+denom1);
}
};
// ----------------------------------------------------------------------------
void btKart::updateFriction(btScalar timeStep)
{
//calculate the impulse, so that the wheels don't move sidewards
int numWheel = getNumWheels();
if (!numWheel)
return;
m_forwardWS.resize(numWheel);
m_axle.resize(numWheel);
m_forwardImpulse.resize(numWheel);
m_sideImpulse.resize(numWheel);
int numWheelsOnGround = 0;
//collapse all those loops into one!
for (int i=0;i<getNumWheels();i++)
{
btWheelInfo& wheelInfo = m_wheelInfo[i];
class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
if (groundObject)
numWheelsOnGround++;
m_sideImpulse[i] = btScalar(0.);
m_forwardImpulse[i] = btScalar(0.);
}
{
for (int i=0;i<getNumWheels();i++)
{
btWheelInfo& wheelInfo = m_wheelInfo[i];
class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
if (groundObject)
{
const btTransform& wheelTrans = getWheelTransformWS( i );
btMatrix3x3 wheelBasis0 = wheelTrans.getBasis();
m_axle[i] = btVector3(
wheelBasis0[0][m_indexRightAxis],
wheelBasis0[1][m_indexRightAxis],
wheelBasis0[2][m_indexRightAxis]);
const btVector3& surfNormalWS = wheelInfo.m_raycastInfo.m_contactNormalWS;
btScalar proj = m_axle[i].dot(surfNormalWS);
m_axle[i] -= surfNormalWS * proj;
m_axle[i] = m_axle[i].normalize();
m_forwardWS[i] = surfNormalWS.cross(m_axle[i]);
m_forwardWS[i].normalize();
resolveSingleBilateral(*m_chassisBody, wheelInfo.m_raycastInfo.m_contactPointWS,
*groundObject, wheelInfo.m_raycastInfo.m_contactPointWS,
btScalar(0.), m_axle[i],m_sideImpulse[i],timeStep);
//m_sideImpulse[i] *= sideFrictionStiffness2; // hiker: sideFrictionStiffness2 is a global(!) variable = 1.0
}
}
}
btScalar sideFactor = btScalar(1.);
btScalar fwdFactor = 0.5;
{
for (int wheel =0;wheel <getNumWheels();wheel++)
{
btWheelInfo& wheelInfo = m_wheelInfo[wheel];
class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
btScalar rollingFriction = 0.f;
if (groundObject)
{
if (wheelInfo.m_engineForce != 0.f)
{
rollingFriction = wheelInfo.m_engineForce* timeStep;
} else
{
btScalar defaultRollingFrictionImpulse = 0.f;
btScalar maxImpulse = wheelInfo.m_brake ? wheelInfo.m_brake : defaultRollingFrictionImpulse;
btWheelContactPoint contactPt(m_chassisBody,groundObject,wheelInfo.m_raycastInfo.m_contactPointWS,m_forwardWS[wheel],maxImpulse);
rollingFriction = calcRollingFriction(contactPt);
}
}
//switch between active rolling (throttle), braking and non-active rolling friction (no throttle/break)
m_forwardImpulse[wheel] = btScalar(0.);
m_wheelInfo[wheel].m_skidInfo= btScalar(1.);
if (groundObject)
{
m_forwardImpulse[wheel] = rollingFriction;//wheelInfo.m_engineForce* timeStep;
}
}
}
// apply the impulses
{
for (int wheel = 0;wheel<getNumWheels() ; wheel++)
{
btWheelInfo& wheelInfo = m_wheelInfo[wheel];
btVector3 rel_pos = wheelInfo.m_raycastInfo.m_contactPointWS -
m_chassisBody->getCenterOfMassPosition();
if (m_forwardImpulse[wheel] != btScalar(0.))
{
m_chassisBody->applyImpulse(m_forwardWS[wheel]*(m_forwardImpulse[wheel]),rel_pos);
}
if (m_sideImpulse[wheel] != btScalar(0.))
{
class btRigidBody* groundObject = (class btRigidBody*) m_wheelInfo[wheel].m_raycastInfo.m_groundObject;
btVector3 rel_pos2 = wheelInfo.m_raycastInfo.m_contactPointWS -
groundObject->getCenterOfMassPosition();
btVector3 sideImp = m_axle[wheel] * m_sideImpulse[wheel];
rel_pos[2] *= wheelInfo.m_rollInfluence;
m_chassisBody->applyImpulse(sideImp,rel_pos);
//apply friction impulse on the ground
groundObject->applyImpulse(-sideImp,rel_pos2);
}
}
}
}

View File

@ -0,0 +1,44 @@
/*
* Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/
*
* Permission to use, copy, modify, distribute and sell this software
* and its documentation for any purpose is hereby granted without fee,
* provided that the above copyright notice appear in all copies.
* Erwin Coumans makes no representations about the suitability
* of this software for any purpose.
* It is provided "as is" without express or implied warranty.
*/
#ifndef BT_KART_H
#define BT_KART_H
#include "BulletDynamics/Dynamics/btRigidBody.h"
#include "btVehicleRaycaster.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "btRaycastVehicle.h"
class btDynamicsWorld;
struct btWheelInfo;
/** The btKart is a raycast vehicle, that does not skid. It therefore solves
* the problems with the plain bullet physics that karts would often rotate
* on a spot if one of the wheels loses contact with the ground.
*/
class btKart : public btRaycastVehicle
{
void defaultInit(const btVehicleTuning& tuning);
public:
btKart(const btVehicleTuning& tuning,btRigidBody* chassis,
btVehicleRaycaster* raycaster );
virtual ~btKart() ;
btScalar rayCast(btWheelInfo& wheel);
virtual void updateVehicle(btScalar step);
void resetSuspension();
void setRaycastWheelInfo(int wheelIndex , bool isInContact,
const btVector3& hitPoint,
const btVector3& hitNormal,btScalar depth);
void setPitchControl(btScalar pitch) { m_pitchControl = pitch; }
void updateSuspension(btScalar deltaTime);
virtual void updateFriction(btScalar timeStep);
};
#endif //BT_KART_H

View File

@ -23,7 +23,7 @@ class btVehicleTuning;
///rayCast vehicle, very special constraint that turn a rigidbody into a vehicle.
class btRaycastVehicle : public btTypedConstraint
{
protected:
btAlignedObjectArray<btVector3> m_forwardWS;
btAlignedObjectArray<btVector3> m_axle;
btAlignedObjectArray<btScalar> m_forwardImpulse;
@ -49,7 +49,9 @@ public:
btScalar m_frictionSlip;
};
private:
// FIXME: can this protected become private again??
protected:
btScalar m_tau;
btScalar m_damping;

View File

@ -212,6 +212,8 @@ libbulletdynamics_a_SOURCES = \
BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp \
BulletDynamics/Dynamics/btSimpleDynamicsWorld.h \
BulletDynamics/Dynamics/Bullet-C-API.cpp \
BulletDynamics/Vehicle/btKart.cpp \
BulletDynamics/Vehicle/btKart.h \
BulletDynamics/Vehicle/btRaycastVehicle.cpp \
BulletDynamics/Vehicle/btRaycastVehicle.h \
BulletDynamics/Vehicle/btVehicleRaycaster.h \

View File

@ -39,6 +39,7 @@ subject to the following restrictions:
///Vehicle simulation, with wheel contact simulated by raycasts
#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
#include "BulletDynamics/Vehicle/btKart.h"

View File

@ -519,6 +519,10 @@
<Filter
Name="Vehicle"
>
<File
RelativePath="..\..\bullet\src\BulletDynamics\Vehicle\btKart.cpp"
>
</File>
<File
RelativePath="..\..\bullet\src\BulletDynamics\Vehicle\btRaycastVehicle.cpp"
>
@ -1117,6 +1121,10 @@
<Filter
Name="Vehicle"
>
<File
RelativePath="..\..\bullet\src\BulletDynamics\Vehicle\btKart.h"
>
</File>
<File
RelativePath="..\..\bullet\src\BulletDynamics\Vehicle\btRaycastVehicle.h"
>

View File

@ -1154,6 +1154,10 @@
RelativePath="..\..\modes\standard_race.cpp"
>
</File>
<File
RelativePath="..\..\modes\three_strikes_battle.cpp"
>
</File>
<File
RelativePath="..\..\modes\world.cpp"
>
@ -1752,6 +1756,10 @@
RelativePath="..\..\modes\standard_race.hpp"
>
</File>
<File
RelativePath="..\..\modes\three_strikes_battle.hpp"
>
</File>
<File
RelativePath="..\..\modes\world.hpp"
>

View File

@ -183,9 +183,9 @@ void Kart::createPhysics(ssgEntity *obj)
// -------------------------
m_vehicle_raycaster =
new btDefaultVehicleRaycaster(RaceManager::getWorld()->getPhysics()->getPhysicsWorld());
m_tuning = new btRaycastVehicle::btVehicleTuning();
m_tuning = new btKart::btVehicleTuning();
m_tuning->m_maxSuspensionTravelCm = m_kart_properties->getSuspensionTravelCM();
m_vehicle = new btRaycastVehicle(*m_tuning, m_body, m_vehicle_raycaster);
m_vehicle = new btKart(*m_tuning, m_body, m_vehicle_raycaster);
// never deactivate the vehicle
m_body->setActivationState(DISABLE_DEACTIVATION);
@ -468,7 +468,7 @@ void Kart::handleExplosion(const Vec3& pos, bool direct_hit)
btVector3 diff((float)(rand()%16/16), (float)(rand()%16/16), 2.0f);
diff.normalize();
diff*=stk_config->m_explosion_impulse/5.0f;
this->m_uprightConstraint->setDisableTime(10.0f);
m_uprightConstraint->setDisableTime(10.0f);
getVehicle()->getRigidBody()->applyCentralImpulse(diff);
getVehicle()->getRigidBody()->applyTorqueImpulse(btVector3(float(rand()%32*5),
float(rand()%32*5),
@ -515,6 +515,13 @@ void Kart::update(float dt)
m_controls.fire = false;
}
// Only use the upright constraint if the kart is in the air!
if(isOnGround())
m_uprightConstraint->setLimit(M_PI);
else
m_uprightConstraint->setLimit(m_kart_properties->getUprightTolerance());
m_zipper_time_left = m_zipper_time_left>0.0f ? m_zipper_time_left-dt : 0.0f;
//m_wheel_rotation gives the rotation around the X-axis, and since velocity's
@ -609,8 +616,8 @@ void Kart::update(float dt)
herring_manager->hitHerring(this);
processSkidMarks();
}
//-----------------------------------------------------------------------------
// Set zipper time, and apply one time additional speed boost
void Kart::handleZipper()

View File

@ -61,10 +61,10 @@ protected:
// is disabled to allow the karts to bounce back
// physics parameters, storing it saves time
btRaycastVehicle::btVehicleTuning *m_tuning;
btKart::btVehicleTuning *m_tuning;
btCompoundShape m_kart_chassis;
btVehicleRaycaster *m_vehicle_raycaster;
btRaycastVehicle *m_vehicle;
btKart *m_vehicle;
btUprightConstraint *m_uprightConstraint;
private:
@ -187,7 +187,7 @@ public:
float getKartLength () const {return m_kart_properties->getKartLength();}
float getKartHeight () const {return m_kart_properties->getKartHeight();}
float getWheelieAngle () const {return m_wheelie_angle; }
btRaycastVehicle *getVehicle () const {return m_vehicle; }
btKart *getVehicle () const {return m_vehicle; }
btUprightConstraint *getUprightConstraint() const {return m_uprightConstraint;}
void draw ();
bool isInRest () const;

View File

@ -201,6 +201,7 @@ void KartProperties::getAllData(const lisp::Lisp* lisp)
lisp->get("jump-velocity", m_jump_velocity );
lisp->get("upright-tolerance", m_upright_tolerance );
lisp->get("upright-max-force", m_upright_max_force );
lisp->get("track-connection-force", m_track_connection_accel );
lisp->getVector("groups", m_groups );
if(m_groups.size()==0)
m_groups.push_back("standard");
@ -268,6 +269,7 @@ void KartProperties::init_defaults()
m_gear_power_increase = stk_config->m_gear_power_increase;
m_upright_tolerance = stk_config->getUprightTolerance();
m_upright_max_force = stk_config->getUprightMaxForce();
m_track_connection_accel = 0.0f; //FIXME
m_camera_max_accel = stk_config->getCameraMaxAccel();
m_camera_max_brake = stk_config->getCameraMaxBrake();
m_camera_distance = stk_config->getCameraDistance();

View File

@ -29,46 +29,61 @@
class Material;
class ssgEntity;
/** This class stores the properties of a kart. This includes size, name,
* identifier, physical properties etc. It is atm also the base class for
* STKConfig, which stores the default values for all physics constants.
*/
class KartProperties : public NoCopy
{
private:
Material *m_icon_material;
ssgEntity *m_model;
std::vector<std::string> m_groups; // list of all groups the kart belongs to
Material *m_icon_material; /**< The icon texture to use. */
ssgEntity *m_model; /**< The 3d model of the kart.*/
std::vector<std::string> m_groups; /**< List of all groups the kart
belongs to. */
protected:
// Display and gui
// ---------------
std::string m_name; // The human readable Name of the karts driver
std::string m_ident; // The computer readable-name of the karts driver
std::string m_model_file; // Filename of 3d model that is used for kart
std::string m_icon_file; // Filename of icon that represents the kart in
// the statusbar and the character select screen
std::string m_shadow_file; // Filename of the image file that contains the
// shadow for this kart
Vec3 m_color; // Color the represents the kart in the status
// bar and on the track-view
std::string m_name; /**< The human readable Name of the kart
* driver. */
std::string m_ident; /**< The computer readable-name of the kart
* driver. */
std::string m_model_file; /**< Filename of 3d model that is used for
* kart.*/
std::string m_icon_file; /**< Filename of icon that represents the kart
* in the statusbar and the character select
* screen. */
std::string m_shadow_file; /**< Filename of the image file that contains
* the shadow for this kart. */
Vec3 m_color; /**< Color the represents the kart in the status
* bar and on the track-view. */
// Physic properties
// -----------------
float m_kart_width; // width of kart
float m_kart_length; // length of kart
float m_kart_height; // height of kart
float m_mass; // weight of kart
float m_wheel_base; // distance between front and read wheels
float m_engine_power; // maximum force from engine
float m_brake_factor; // braking factor * engine_power = braking force
float m_time_full_steer; // time for player karts to reach full steer angle
float m_wheelie_max_speed_ratio; // percentage of maximum speed for wheelies
float m_wheelie_max_pitch; // maximum pitch for wheelies
float m_wheelie_pitch_rate; // rate/sec with which kart goes up
float m_wheelie_restore_rate; // rate/sec with which kart does down
float m_wheelie_speed_boost; // speed boost while doing a wheelie
float m_wheelie_power_boost; // increase in engine power
float m_kart_width; /**< Width of kart. */
float m_kart_length; /**< Length of kart. */
float m_kart_height; /**< Height of kart. */
float m_mass; /**< Weight of kart. */
float m_wheel_base; /**< Distance between front and rear
* wheels. */
float m_engine_power; /**< Maximum force from engine. */
float m_brake_factor; /**< Braking factor * engine_power =
* braking force. */
float m_time_full_steer; /**< Time for player karts to reach full
* steer angle. */
float m_wheelie_max_speed_ratio; /**< Percentage of maximum speed for
* wheelies. */
float m_wheelie_max_pitch; /**< Maximum pitch for wheelies. */
float m_wheelie_pitch_rate; /**< Rate/sec with which kart goes up. */
float m_wheelie_restore_rate; /**< Rate/sec with which kart does down.*/
float m_wheelie_speed_boost; /**< Speed boost while doing a wheelie. */
float m_wheelie_power_boost; /**< Increase in engine power. */
float m_min_speed_turn, m_angle_at_min; // speed dependent steering: max
float m_max_speed_turn, m_angle_at_max; // turn angle at lowest speed etc
float m_min_speed_turn, m_angle_at_min; /**< Speed dependent steering:
* maximum speed to use. */
float m_max_speed_turn, m_angle_at_max; /**< Turn angle at lowest speed
* etc. */
float m_speed_angle_increase;
// bullet physics data
@ -83,10 +98,13 @@ protected:
float m_chassis_angular_damping;
float m_maximum_speed;
float m_max_speed_reverse_ratio;
Vec3 m_gravity_center_shift; // shift of center of gravity
Vec3 m_front_wheel_connection; // connection point relative to center of
Vec3 m_rear_wheel_connection; // gravity for front and rear right wheels
// (X is mirrored for left wheels)
Vec3 m_gravity_center_shift; /**< Shift of center of gravity. */
Vec3 m_front_wheel_connection; /**< Connection point relative to center of */
Vec3 m_rear_wheel_connection; /**< Gravity for front and rear right wheels
* (X is mirrored for left wheels). */
float m_track_connection_accel; /**< Artifical acceleration that pulls a
* kart down onto the track if one axis
* loses contact with the track. */
float m_suspension_rest;
float m_suspension_travel_cm;
float m_jump_velocity; // z velocity set when jumping
@ -98,14 +116,14 @@ protected:
float m_camera_max_accel; // maximum acceleration of camera
float m_camera_max_brake; // maximum braking of camera
float m_camera_distance; // distance of normal camera from kart
//
// The following two vectors define at what ratio of the maximum speed what
// gear is selected, e.g. 0.25 means: if speed <=0.25*maxSpeed --> gear 1,
// 0.5 means: if speed <=0.5 *maxSpeed --> gear 2
// The next vector contains the increase in max power (to simulate different
// gears), e.g. 2.5 as first entry means: 2.5*maxPower in gear 1
std::vector<float> m_gear_switch_ratio;
std::vector<float> m_gear_power_increase;
/** The following two vectors define at what ratio of the maximum speed what
* gear is selected. E.g. 0.25 means: if speed <=0.25*maxSpeed --> gear 1,
* 0.5 means: if speed <=0.5 *maxSpeed --> gear 2
* The next vector contains the increase in max power (to simulate different
* gears), e.g. 2.5 as first entry means: 2.5*maxPower in gear 1 */
std::vector<float> m_gear_switch_ratio,
m_gear_power_increase;
public:
@ -163,6 +181,7 @@ public:
float getJumpVelocity () const {return m_jump_velocity; }
float getUprightTolerance () const {return m_upright_tolerance; }
float getUprightMaxForce () const {return m_upright_max_force; }
float getTrackConnectionForce () const {return m_track_connection_accel; }
const std::vector<float>&
getGearSwitchRatio () const {return m_gear_switch_ratio; }
const std::vector<float>&

View File

@ -23,7 +23,7 @@
#include "modes/world.hpp"
#include <string>
class KartIconDisplayInfo;
struct KartIconDisplayInfo;
struct BattleInfo
{

View File

@ -75,7 +75,7 @@ Physics::~Physics()
* \param kart The kart to add.
* \param vehicle The raycast vehicle object.
*/
void Physics::addKart(const Kart *kart, btRaycastVehicle *vehicle)
void Physics::addKart(const Kart *kart, btKart *vehicle)
{
m_dynamics_world->addRigidBody(kart->getBody());
m_dynamics_world->addVehicle(vehicle);

View File

@ -95,7 +95,7 @@ public:
Physics ();
~Physics ();
void init (const Vec3 &min_world, const Vec3 &max_world);
void addKart (const Kart *k, btRaycastVehicle *v);
void addKart (const Kart *k, btKart *v);
void addBody (btRigidBody* b) {m_dynamics_world->addRigidBody(b);}
void removeKart (const Kart *k);
void removeBody (btRigidBody* b) {m_dynamics_world->removeRigidBody(b);}

View File

@ -248,7 +248,7 @@ public:
if(isBattleMode(type)) return false;
const int id = (int)type;
const int answer = (id-1000)/100;
return (bool)answer;
return answer!=0;
}
};

View File

@ -129,6 +129,7 @@ void STKConfig::load(const std::string filename)
CHECK_NEG(m_explosion_impulse_objects, "explosion-impulse-objects" );
CHECK_NEG(m_upright_tolerance, "upright-tolerance" );
CHECK_NEG(m_upright_max_force, "upright-max-force" );
CHECK_NEG(m_track_connection_accel, "track-connection-force" );
CHECK_NEG(m_camera_max_accel, "camera-max-accel" );
CHECK_NEG(m_camera_max_brake, "camera-max-brake" );
CHECK_NEG(m_camera_distance, "camera-distance" );
@ -164,7 +165,7 @@ void STKConfig::init_defaults()
m_maximum_speed = m_suspension_rest =
m_max_speed_reverse_ratio = m_explosion_impulse = m_jump_velocity =
m_explosion_impulse_objects = m_upright_tolerance = m_upright_max_force =
m_suspension_travel_cm =
m_suspension_travel_cm = m_track_connection_accel =
// Camera
m_camera_max_accel = m_camera_max_brake = m_camera_distance = UNDEFINED;
m_gravity_center_shift = Vec3(UNDEFINED);