Bullet only:

1) Added bullet collision handling, e.g. rocket hits are now
   detected by bullet code, bombs will be passed on etc.
2) Rockets are now handled by bullet as well.
3) Moved expected location of bullet from STK/bullet to
   STK/src/bullet.


git-svn-id: svn+ssh://svn.code.sf.net/p/supertuxkart/code/trunk/supertuxkart@1280 178a84e3-b1eb-0310-8ba1-8eac791a3b58
This commit is contained in:
hikerstk 2007-11-03 13:13:26 +00:00
parent 3eeac7bec0
commit b5c7b8233b
17 changed files with 460 additions and 174 deletions

View File

@ -1,25 +1,29 @@
Preliminary support for the bullet physics engine has been
added. To enable it (assume that 'STK' is the supertuxkart root
directory):
1) Decompress version r528 of bullet in STK/trunk/bullet
(the API of bullet is changing, and STK hasn't been updated
to use a recent bullet version yet. So new bullet versions
will most likely not compile and/or not work).
2) Compile bullet (follow the instructions in STK/trunk/bullet/INSTALL)
3) Run configure with:
1) Uncompress a recent version of bullet (tested with 2.63)
in STK/src/bullet
2.63 is the latest version, earlier versions will not
work due to changes in the bullet API.
NOTE: The location of bullet was changed, before it was in
STK/bullet, now it's in STK/src/bullet.
2) Compile bullet (follow the instructions in STK/src/bullet/INSTALL)
3) Run STK configure with:
./configure --enable-bullet
4) make
For now mainly the race track works as expected, all tracks
can be played (though the performance in some tracks is somewhat
bad at the moment). Most important bugs:
- collectable don't work
(well, you can fire a rocket, but hitting a kart won't do
much, zipper, don't do anything, ...)
- not all collectable work
(zippers don't work, homing missiles don't go to the target,
sparks won't fly as expected either), but collision with
karts work.
- no proper friction handling, so no skidding
(though skidding potentially works - if the friction is
set correctly).
- physics parameters are not tuned
- physics parameters have been improved, but might need
additional tuning
- rescuing an upside-down kart will return the kart to the middle
of the track (waypoints) - the kart should be returned to where
it ended, just with a proper orientation.

View File

@ -359,8 +359,8 @@ AC_ARG_ENABLE(bullet,
if test "x${enable_bullet}" != "xno"; then
AC_DEFINE([BULLET], [], [Use the bullet physics engine])
AC_MSG_RESULT([enabled])
CXXFLAGS="$CXXFLAGS -I../bullet/src"
LIBS="$LIBS -L ../bullet/out/*/*/libs -lbulletopenglsupport -lbulletdynamics -lbulletcollision -lbulletmath -lglut"
CXXFLAGS="$CXXFLAGS -Ibullet/src"
LIBS="$LIBS -L bullet/out/*/*/libs -lbulletopenglsupport -lbulletdynamics -lbulletcollision -lbulletmath -lglut"
else
AC_MSG_RESULT([disabled])
fi

View File

@ -137,6 +137,7 @@ void CollectableManager::LoadNode(const lisp::Lisp* lisp, int collectType )
ssgEntity* e = loader->load(sModel, CB_COLLECTABLE);
m_all_models[collectType] = e;
e->ref();
e->clrTraversalMaskBits(SSGTRAV_ISECT|SSGTRAV_HOT);
}
else
{

View File

@ -72,5 +72,7 @@
# define M_PI 3.14159265358979323846f /* As in Linux's math.h */
#endif
#define NINETY_DEGREE_RAD (M_PI/2.0f)
#define DEGREE_TO_RAD(x) ((x)*M_PI/180.0f)
#endif

View File

@ -82,10 +82,10 @@ void GameManager::run()
if (race_manager->raceIsActive())
{
scene->draw((m_curr_time - m_prev_time ) * 0.001);
scene->draw((m_curr_time - m_prev_time ) * 0.001f);
if ( world->getPhase() != World::LIMBO_PHASE)
{
world->update((m_curr_time - m_prev_time ) * 0.001);
world->update((m_curr_time - m_prev_time ) * 0.001f);
if(user_config->m_profile)
{

View File

@ -38,7 +38,7 @@
#include "gui/race_gui.hpp"
#include "translation.hpp"
#ifdef BULLET
#include "../bullet/Demos/OpenGL/GL_ShapeDrawer.h"
#include "bullet/Demos/OpenGL/GL_ShapeDrawer.h"
#endif
#if defined(WIN32) && !defined(__CYGWIN__)
# define snprintf _snprintf
@ -174,16 +174,16 @@ void Kart::createPhysics(ssgEntity *obj)
float x_min, x_max, y_min, y_max, z_min, z_max;
MinMax(obj, &x_min, &x_max, &y_min, &y_max, &z_min, &z_max);
float kart_width = x_max-x_min;
float kart_length = y_max-y_min;
if(kart_length<1.2) kart_length=1.5f;
m_kart_length = y_max-y_min;
if(m_kart_length<1.2) m_kart_length=1.5f;
// The kart height is needed later to reset the physics to the correct
// position.
m_kart_height = z_max-z_min;
btBoxShape *shape = new btBoxShape(btVector3(0.5*kart_width,
0.5*kart_length,
0.5*m_kart_height));
btBoxShape *shape = new btBoxShape(btVector3(0.5f*kart_width,
0.5f*m_kart_length,
0.5f*m_kart_height));
btTransform shiftCenterOfGravity;
shiftCenterOfGravity.setIdentity();
// Shift center of gravity downwards, so that the kart
@ -199,14 +199,12 @@ void Kart::createPhysics(ssgEntity *obj)
// Set mass and inertia
// --------------------
float mass=getMass();
btVector3 inertia;
m_kart_chassis->calculateLocalInertia(mass, inertia);
// Position the chassis
// --------------------
btTransform trans;
trans.setIdentity();
createBody(mass, trans, m_kart_chassis, inertia);
createBody(mass, trans, m_kart_chassis, Moveable::MOV_KART);
m_body->setDamping(m_kart_properties->getChassisLinearDamping(),
m_kart_properties->getChassisAngularDamping() );
@ -222,6 +220,7 @@ void Kart::createPhysics(ssgEntity *obj)
new btDefaultVehicleRaycaster(world->getPhysics()->getPhysicsWorld());
m_tuning = new btRaycastVehicle::btVehicleTuning();
m_vehicle = new btRaycastVehicle(*m_tuning, m_body, m_vehicle_raycaster);
// never deactivate the vehicle
m_body->setActivationState(DISABLE_DEACTIVATION);
m_vehicle->setCoordinateSystem(/*right: */ 0, /*up: */ 2, /*forward: */ 1);
@ -231,13 +230,13 @@ void Kart::createPhysics(ssgEntity *obj)
float wheel_width = m_kart_properties->getWheelWidth();
float wheel_radius = m_kart_properties->getWheelRadius();
float suspension_rest = m_kart_properties->getSuspensionRest();
float connection_height = -(0.5-CENTER_SHIFT)*m_kart_height;
float connection_height = -(0.5f-CENTER_SHIFT)*m_kart_height;
btVector3 wheel_direction(0.0f, 0.0f, -1.0f);
btVector3 wheel_axle(1.0f,0.0f,0.0f);
// right front wheel
btVector3 wheel_coord(0.5f*kart_width-0.3f*wheel_width,
0.5f*kart_length-wheel_radius,
0.5f*m_kart_length-wheel_radius,
connection_height);
m_vehicle->addWheel(wheel_coord, wheel_direction, wheel_axle,
suspension_rest, wheel_radius, *m_tuning,
@ -245,23 +244,23 @@ void Kart::createPhysics(ssgEntity *obj)
// left front wheel
wheel_coord = btVector3(-0.5f*kart_width+0.3f*wheel_width,
0.5f*kart_length-wheel_radius,
0.5f*m_kart_length-wheel_radius,
connection_height);
m_vehicle->addWheel(wheel_coord, wheel_direction, wheel_axle,
suspension_rest, wheel_radius, *m_tuning,
/* isFrontWheel: */ true);
// right rear wheel
wheel_coord = btVector3(0.5*kart_width-0.3f*wheel_width,
-0.5*kart_length+wheel_radius,
wheel_coord = btVector3(0.5f*kart_width-0.3f*wheel_width,
-0.5f*m_kart_length+wheel_radius,
connection_height);
m_vehicle->addWheel(wheel_coord, wheel_direction, wheel_axle,
suspension_rest, wheel_radius, *m_tuning,
/* isFrontWheel: */ false);
// right rear wheel
wheel_coord = btVector3(-0.5*kart_width+0.3f*wheel_width,
-0.5*kart_length+wheel_radius,
wheel_coord = btVector3(-0.5f*kart_width+0.3f*wheel_width,
-0.5f*m_kart_length+wheel_radius,
connection_height);
m_vehicle->addWheel(wheel_coord, wheel_direction, wheel_axle,
suspension_rest, wheel_radius, *m_tuning,
@ -304,6 +303,7 @@ Kart::~Kart()
#ifdef BULLET
delete m_tuning;
delete m_vehicle_raycaster;
world->getPhysics()->removeKart(this);
delete m_vehicle;
for(int i=0; i<m_kart_chassis->getNumChildShapes(); i++)
{
@ -394,11 +394,11 @@ void Kart::reset()
trans->setIdentity();
// Set heading:
trans->setRotation(btQuaternion(btVector3(0.0f, 0.0f, 1.0f),
m_reset_pos.hpr[0]*3.1415926f/180.0f));
DEGREE_TO_RAD(m_reset_pos.hpr[0])) );
// Set position
trans->setOrigin(btVector3(m_reset_pos.xyz[0],
m_reset_pos.xyz[1],
m_reset_pos.xyz[2]+0.5*m_kart_height));
m_reset_pos.xyz[2]+0.5f*m_kart_height));
m_vehicle->applyEngineForce (0.0f, 2);
m_vehicle->applyEngineForce (0.0f, 3);
m_body->setCenterOfMassTransform(*trans);
@ -640,6 +640,7 @@ void Kart::forceCrash ()
} // forceCrash
//-----------------------------------------------------------------------------
#ifndef BULLET
void Kart::doCollisionAnalysis ( float delta, float hot )
{
if ( m_collided )
@ -670,7 +671,7 @@ void Kart::doCollisionAnalysis ( float delta, float hot )
m_velocity.xyz[2] = 0.0f ;
} // isOnGround
} // doCollisionAnalysis
#endif
//-----------------------------------------------------------------------------
void Kart::update (float dt)
{
@ -705,7 +706,7 @@ void Kart::update (float dt)
#ifdef BULLET
m_rescue_pitch = m_curr_pos.hpr[1];
m_rescue_roll = m_curr_pos.hpr[2];
world->getPhysics()->removeKart(this, m_vehicle);
world->getPhysics()->removeKart(this);
#endif
}
#ifdef BULLET
@ -713,13 +714,13 @@ void Kart::update (float dt)
btTransform pos=m_body->getCenterOfMassTransform();
pos.setOrigin(btVector3(m_curr_pos.xyz[0],m_curr_pos.xyz[1],m_curr_pos.xyz[2]));
btQuaternion q_roll (btVector3(0., 1., 0.),
-m_rescue_roll*dt/rescue_time*M_PI/180.0);
btQuaternion q_pitch(btVector3(1., 0., 0.),
-m_rescue_pitch*dt/rescue_time*M_PI/180.0);
btQuaternion q_roll (btVector3(0.f, 1.f, 0.f),
-m_rescue_roll*dt/rescue_time*M_PI/180.0f);
btQuaternion q_pitch(btVector3(1.f, 0.f, 0.f),
-m_rescue_pitch*dt/rescue_time*M_PI/180.0f);
pos.setRotation(pos.getRotation()*q_roll*q_pitch);
m_body->setCenterOfMassTransform(pos);
m_motion_state->setWorldTransform(pos);
setTrans(pos);
//printf("Set %f %f %f\n",pos.getOrigin().x(),pos.getOrigin().y(),pos.getOrigin().z());
#else
sgZeroVec3 ( m_velocity.xyz ) ;
@ -848,14 +849,14 @@ void Kart::draw()
{
float m[16];
btTransform t;
m_motion_state->getWorldTransform(t);
getTrans(&t);
t.getOpenGLMatrix(m);
btVector3 wire_color(0.5f, 0.5f, 0.5f);
world->getPhysics()->debugDraw(m, m_body->getCollisionShape(),
wire_color);
btCylinderShapeX *wheelShape =
new btCylinderShapeX( btVector3(0.3,
new btCylinderShapeX( btVector3(0.3f,
m_kart_properties->getWheelRadius(),
m_kart_properties->getWheelRadius()) );
btVector3 wheelColor(1,0,0);
@ -923,7 +924,7 @@ void Kart::updatePhysics (float dt)
#ifdef BULLET
float engine_power = getActualWheelForce() + handleWheelie(dt);
if(m_attachment.getType()==ATTACH_PARACHUTE) engine_power*=0.2;
if(m_attachment.getType()==ATTACH_PARACHUTE) engine_power*=0.2f;
if(m_controls.accel)
{ // accelerating
@ -967,10 +968,10 @@ void Kart::updatePhysics (float dt)
btVector3 velocity = m_body->getLinearVelocity();
velocity.setZ( 3.0f );
getVehicle()->getRigidBody()->setLinearVelocity( velocity );
getBody()->setLinearVelocity( velocity );
}
const float steering = getMaxSteerAngle() * m_controls.lr * 0.00444;
const float steering = getMaxSteerAngle() * m_controls.lr * 0.00444f;
m_vehicle->setSteeringValue(steering, 0);
m_vehicle->setSteeringValue(steering, 1);
@ -1073,7 +1074,7 @@ void Kart::updatePhysics (float dt)
// ----------------------------------------------
const float FORCE_ON_REAR_TIRE = 0.5f*MASS*WORLD_GRAVITY + m_prev_accel*MASS*getHeightCOG()/WHEEL_BASE;
const float FORCE_ON_FRONT_TIRE = MASS*WORLD_GRAVITY - FORCE_ON_REAR_TIRE;
float maxGrip = std::max(FORCE_ON_REAR_TIRE,FORCE_ON_FRONT_TIRE)*getTireGrip();
float maxGrip = std::max(FORCE_ON_REAR_TIRE,FORCE_ON_FRONT_TIRE)*getTireGrip();
// If the kart is on ground, modify the grip by the friction
// modifier for the texture/terrain.
@ -1272,9 +1273,9 @@ void Kart::endRescue()
// by the kart being upside down??
btTransform pos=m_body->getCenterOfMassTransform();
pos.setOrigin(btVector3(m_curr_pos.xyz[0],m_curr_pos.xyz[1],
m_curr_pos.xyz[2]+0.5*m_kart_height));
m_curr_pos.xyz[2]+0.5f*m_kart_height));
m_body->setCenterOfMassTransform(pos);
m_motion_state->setWorldTransform(pos);
setTrans(pos);
#endif
@ -1518,12 +1519,13 @@ void Kart::placeModel ()
btTransform t;
if(m_rescue)
{
// FIXME: can we use motion_state/getTrans as below here?
// FIXME: e.g. by setting motion_state appropriately during rescue?
t=m_body->getCenterOfMassTransform();
// m_motion_state->getWorldTransform(t);
}
else
{
m_motion_state->getWorldTransform(t);
getTrans(&t);
}
float m[4][4];
t.getOpenGLMatrix((float*)&m);
@ -1539,7 +1541,7 @@ void Kart::placeModel ()
// c.hpr[1] += m_wheelie_angle ;
// c.xyz[2] += 0.3f*fabs(sin(m_wheelie_angle*SG_DEGREES_TO_RADIANS));
const float CENTER_SHIFT = getGravityCenterShift();
c.xyz[2] -= (0.5-CENTER_SHIFT)*m_kart_height; // adjust for center of gravity
c.xyz[2] -= (0.5f-CENTER_SHIFT)*m_kart_height; // adjust for center of gravity
m_model->setTransform(&c);
// Check if a kart needs to be rescued.
@ -1597,7 +1599,7 @@ void Kart::handleMagnet(float cdist, int closest)
float tgt_velocity = world->getKart(closest)->getVelocity()->xyz[1] ;
//JH FIXME: that should probably be changes, e.g. by increasing the throttle
//JH FIXME: that should probably be changed, e.g. by increasing the throttle
// to something larger than 1???
if (cdist > stk_config->m_magnet_min_range_sq)
{

View File

@ -91,6 +91,7 @@ protected:
float m_wheelie_angle ;
float m_current_friction; // current friction
float m_lap_start_time; // Time at start of a new lap
float m_kart_length; // length of kart
char m_fastest_lap_message[255];
int m_shortcut_count; // counts number of times a shortcut is used
int m_shortcut_sector; // segment on which the shortcut was started
@ -229,8 +230,10 @@ public:
float getMaxSpeed () const {return m_max_speed; }
void setTimeAtLap (float t){m_time_at_last_lap=t; }
float getTimeAtLap () const {return m_time_at_last_lap; }
float getKartLength () const {return m_kart_length; }
void createPhysics (ssgEntity *obj);
#ifdef BULLET
float getKartHeight () const {return m_kart_height; }
btRaycastVehicle *getVehicle () const {return m_vehicle; }
void updateBulletPhysics(float dt);
void draw ();
@ -253,7 +256,9 @@ public:
virtual void forceCrash ();
virtual void doLapCounting ();
virtual void update (float dt );
#ifndef BULLET
virtual void doCollisionAnalysis(float dt, float hot );
#endif
virtual void doObjectInteractions();
virtual void OutsideTrack (int isReset) {m_rescue=true;}
};

View File

@ -85,15 +85,19 @@ void Moveable::reset ()
//-----------------------------------------------------------------------------
#ifdef BULLET
void Moveable::createBody(float mass, btTransform& position,
btCollisionShape *shape, btVector3 inertia) {
void Moveable::createBody(float mass, btTransform& trans,
btCollisionShape *shape, MoveableType m) {
m_motion_state = new btDefaultMotionState(position);
btVector3 inertia;
shape->calculateLocalInertia(mass, inertia);
m_motion_state = new btDefaultMotionState(trans);
// Then create a rigid body
// ------------------------
m_body = new btRigidBody(mass, m_motion_state,
shape, inertia);
m_body->setUserPointer(this);
setMoveableType(m);
} // createBody
#endif
//-----------------------------------------------------------------------------
@ -174,11 +178,17 @@ void Moveable::update (float dt)
#ifdef BULLET
m_on_ground = ( HAT <= 1.5 );
// FIXME: we need a correct test here, HOT/HAT are currently not defined
// for bullet (and would require a separate raycast, which can be
// expensive. Perhaps add a function to bullet to indicate if
// all/some/?? wheels toucht the ground.
// m_on_ground is currently only used (in the bullet version) for
// the gui display anyway
#else
m_on_ground = ( HAT <= 0.01 );
#endif
doCollisionAnalysis(dt, HOT);
#endif
placeModel () ;
@ -246,7 +256,9 @@ void Moveable::ReadHistory(char* s, int kartNumber, int indx)
} // ReadHistory
//-----------------------------------------------------------------------------
#ifndef BULLET
void Moveable::doCollisionAnalysis ( float,float ) { /* Empty by Default. */ }
#endif
#define ISECT_STEP_SIZE 0.4f
#define COLLISION_SPHERE_RADIUS 0.6f

View File

@ -40,7 +40,10 @@
class Moveable
{
public:
enum MoveableType {MOV_KART, MOV_PROJECTILE} ;
protected:
MoveableType m_moveable_type; /* used when upcasting bullet user pointers */
sgCoord m_reset_pos; /* Where to start in case of a reset */
sgCoord m_curr_pos; /* current position */
sgCoord m_velocity; /* current velocity in local coordinates */
@ -73,6 +76,8 @@ public:
ssgTransform* getModel () {return m_model ; }
int isOnGround () {return m_on_ground; }
MoveableType getMoveableType() const {return m_moveable_type; }
void setMoveableType(MoveableType m){m_moveable_type=m; }
sgCoord* getVelocity () {return & m_velocity; }
sgCoord* getCoord () {return &m_curr_pos; }
const sgCoord* getCoord () const {return &m_curr_pos; }
@ -83,7 +88,9 @@ public:
virtual void reset ();
virtual void update (float dt) ;
virtual void updatePosition(float dt, sgMat4 result);
#ifndef BULLET
virtual void doCollisionAnalysis(float dt, float hot);
#endif
// Gets called when no high of terrain can be determined (isReset=0), or
// there is a 'reset' material under the moveable --> karts need to be
@ -95,8 +102,11 @@ public:
void ReadHistory (char* s, int kartNumber, int indx);
#ifdef BULLET
btRigidBody* getBody () const {return m_body; }
void createBody(float mass, btTransform& position,
btCollisionShape *shape, btVector3 inertia);
void createBody(float mass, btTransform& trans,
btCollisionShape *shape, MoveableType m);
void getTrans (btTransform* t) const
{m_motion_state->getWorldTransform(*t);}
void setTrans (btTransform& t){m_motion_state->setWorldTransform(t);}
#endif
}
; // class Moveable

View File

@ -162,16 +162,16 @@ void MovingPhysics::init()
// -------------------------------
float x_min, x_max, y_min, y_max, z_min, z_max, radius;
MinMax(this, &x_min, &x_max, &y_min, &y_max, &z_min, &z_max);
m_half_height = 0.5*(z_max-z_min);
m_half_height = 0.5f*(z_max-z_min);
switch (m_body_type)
{
case BODY_CONE: radius = 0.5*std::max(x_max-x_min, y_max-y_min);
case BODY_CONE: radius = 0.5f*std::max(x_max-x_min, y_max-y_min);
m_shape = new btConeShape(radius, z_max-z_min);
setName("cone");
break;
case BODY_BOX: m_shape = new btBoxShape(btVector3(0.5*(x_max-x_min),
0.5*(y_max-y_min),
0.5*(z_max-z_min) ) );
case BODY_BOX: m_shape = new btBoxShape(btVector3(0.5f*(x_max-x_min),
0.5f*(y_max-y_min),
0.5f*(z_max-z_min) ) );
setName("box");
break;
case BODY_NONE: fprintf(stderr, "WARNING: Uninitialised moving shape\n");
@ -189,8 +189,7 @@ void MovingPhysics::init()
btVector3 inertia;
m_shape->calculateLocalInertia(mass, inertia);
m_body = new btRigidBody(mass, m_motion_state, m_shape, inertia);
world->getPhysics()->getPhysicsWorld()->addRigidBody(m_body);
world->getPhysics()->addBody(m_body);
} // init
// -----------------------------------------------------------------------------

View File

@ -9,7 +9,7 @@
// of the License, or (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// but WITHOUT ANY WARRANTY; without even the implied warranty ofati
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
@ -20,42 +20,35 @@
#ifdef BULLET
#include "bullet/Demos/OpenGL/GL_ShapeDrawer.h"
#include "physics.hpp"
#include "ssg_help.hpp"
#include "world.hpp"
#include "projectile.hpp"
#include "../bullet/Demos/OpenGL/GL_ShapeDrawer.h"
#include "moving_physics.hpp"
#include "user_config.hpp"
#include "sound_manager.hpp"
/** Initialise physics. */
float Physics::NOHIT=-99999.9f;
Physics::Physics(float gravity)
{
// The bullet interface has changed recently, define NEWBULLET
// for the new interface, default is the old interface. This version
// works with SVN revision 813 of bullet.
#ifdef NEWBULLET
btDefaultCollisionConfiguration* collisionConf = new btDefaultCollisionConfiguration();
btCollisionDispatcher *dispatcher = new btCollisionDispatcher(collisionConf);
#else
btCollisionDispatcher *dispatcher = new btCollisionDispatcher();
#endif
btDefaultCollisionConfiguration* collisionConf
= new btDefaultCollisionConfiguration();
m_dispatcher = new btCollisionDispatcher(collisionConf);
btVector3 worldMin(-1000, -1000, -1000);
btVector3 worldMax( 1000, 1000, 1000);
#ifdef NEWBULLET
btBroadphaseInterface *axis_sweep = new btAxisSweep3(worldMin, worldMax);
btConstraintSolver *constraintSolver = new btSequentialImpulseConstraintSolver();
m_dynamics_world = new btDiscreteDynamicsWorld(dispatcher, axis_sweep,
m_dynamics_world = new btDiscreteDynamicsWorld(m_dispatcher, axis_sweep,
constraintSolver);
#else
btOverlappingPairCache *pairCache = new btAxisSweep3(worldMin, worldMax);
btConstraintSolver *constraintSolver = new btSequentialImpulseConstraintSolver();
m_dynamics_world = new btDiscreteDynamicsWorld(dispatcher, pairCache,
constraintSolver);
#endif
m_dynamics_world->setGravity(btVector3(0.0f, 0.0f, -gravity));
if(user_config->m_bullet_debug)
{
@ -68,6 +61,7 @@ Physics::Physics(float gravity)
//-----------------------------------------------------------------------------
Physics::~Physics()
{
delete m_dispatcher;
delete m_dynamics_world;
} // ~Physics
@ -75,16 +69,28 @@ Physics::~Physics()
//* Convert the ssg track tree into its physics equivalents.
void Physics::setTrack(ssgEntity* track)
{
//return; // debug only FIXME
if(!track) return;
sgMat4 mat;
sgMakeIdentMat4(mat);
convertTrack(track, mat);
btTriangleMesh *track_mesh = new btTriangleMesh();
// Collect all triangles in the track_mesh
convertTrack(track, mat, track_mesh);
// Now convert the triangle mesh into a static rigid body
btCollisionShape *mesh_shape = new btBvhTriangleMeshShape(track_mesh, true);
btTransform startTransform;
startTransform.setIdentity();
btDefaultMotionState *myMotionState = new btDefaultMotionState(startTransform);
btRigidBody *body=new btRigidBody(0.0f, myMotionState, mesh_shape);
// FIXME: can the mesh_shape and or track_mesh be deleted now?
m_dynamics_world->addRigidBody(body);
body->setUserPointer(0);
} // setTrack
// -----------------------------------------------------------------------------
//* Convert the ssg track tree into its physics equivalents.
void Physics::convertTrack(ssgEntity *track, sgMat4 m)
void Physics::convertTrack(ssgEntity *track, sgMat4 m, btTriangleMesh* track_mesh)
{
if(!track) return;
MovingPhysics *mp = dynamic_cast<MovingPhysics*>(track);
@ -98,8 +104,6 @@ void Physics::convertTrack(ssgEntity *track, sgMat4 m)
else if(track->isAKindOf(ssgTypeLeaf()))
{
ssgLeaf *leaf = (ssgLeaf*)(track);
// printf("triangles %d\n",leaf->getNumTriangles());
btTriangleMesh *mesh = new btTriangleMesh();
for(int i=0; i<leaf->getNumTriangles(); i++)
{
short v1,v2,v3;
@ -112,15 +116,9 @@ void Physics::convertTrack(ssgEntity *track, sgMat4 m)
btVector3 vb1(vv1[0],vv1[1],vv1[2]);
btVector3 vb2(vv2[0],vv2[1],vv2[2]);
btVector3 vb3(vv3[0],vv3[1],vv3[2]);
mesh->addTriangle(vb1, vb2, vb3);
track_mesh->addTriangle(vb1, vb2, vb3);
}
btCollisionShape *mesh_shape = new btBvhTriangleMeshShape(mesh, true);
btTransform startTransform;
startTransform.setIdentity();
btDefaultMotionState *myMotionState = new btDefaultMotionState(startTransform);
btRigidBody *body=new btRigidBody(0.0f, myMotionState, mesh_shape);
m_dynamics_world->addRigidBody(body);
} // if(track isAKindOf leaf)
else if(track->isAKindOf(ssgTypeTransform()))
{
@ -131,14 +129,14 @@ void Physics::convertTrack(ssgEntity *track, sgMat4 m)
sgPreMultMat4(tmpM,tmpT);
for(ssgEntity *e = t->getKid(0); e!=NULL; e=t->getNextKid())
{
convertTrack(e, tmpM);
convertTrack(e, tmpM, track_mesh);
} // for i
}
else if (track->isAKindOf(ssgTypeBranch()))
{
ssgBranch *b =(ssgBranch*)track;
for(ssgEntity* e=b->getKid(0); e!=NULL; e=b->getNextKid()) {
convertTrack(e, m);
convertTrack(e, m, track_mesh);
} // for i<getNumKids
}
else
@ -157,13 +155,13 @@ void Physics::addKart(const Kart *kart, btRaycastVehicle *vehicle)
} // addKart
//-----------------------------------------------------------------------------
/** Removes a kart from the physics engine.
* Removes a kart from the physics engine. This is used when rescuing a kart
/** Removes a kart from the physics engine. This is used when rescuing a kart
* (and during cleanup).
*/
void Physics::removeKart(const Kart *kart, btRaycastVehicle *vehicle)
void Physics::removeKart(const Kart *kart)
{
m_dynamics_world->removeRigidBody(kart->getBody());
m_dynamics_world->removeVehicle(vehicle);
m_dynamics_world->removeVehicle(kart->getVehicle());
} // removeKart
//-----------------------------------------------------------------------------
@ -171,9 +169,143 @@ void Physics::update(float dt)
{
m_dynamics_world->stepSimulation(dt);
// ??? m_dynamicsWorld->updateAabbs();
handleCollisions();
} // update
//-----------------------------------------------------------------------------
void Physics::handleCollisions() {
int numManifolds = m_dispatcher->getNumManifolds();
for(int i=0; i<numManifolds; i++)
{
btPersistentManifold* contactManifold = m_dynamics_world->getDispatcher()->getManifoldByIndexInternal(i);
btCollisionObject* objA = static_cast<btCollisionObject*>(contactManifold->getBody0());
btCollisionObject* objB = static_cast<btCollisionObject*>(contactManifold->getBody1());
contactManifold->refreshContactPoints(objA->getWorldTransform(),objB->getWorldTransform());
int numContacts = contactManifold->getNumContacts();
if(!numContacts) continue; // no real collision
Moveable *movA = static_cast<Moveable*>(objA->getUserPointer());
Moveable *movB = static_cast<Moveable*>(objB->getUserPointer());
// 1) object A is a track
// =======================
if(!movA)
{
if(!movB)
{ // 1.1) track hits track ??
// ------------------------
continue; // --> ignore
}
else if(movB->getMoveableType()==Moveable::MOV_PROJECTILE)
{ // 1.2 projectile hits track
// -------------------------
Projectile *p=(Projectile*)movB;
p->explode(NULL); // explode on track
}
else
{ // 1.3 kart hits track
// -------------------
continue;
}
}
// 2) object a is a kart
// =====================
else if(movA->getMoveableType()==Moveable::MOV_KART)
{
if(!movB)
{ // 2.1) kart hits track
// --------------------
continue; // --> ignore
}
else if(movB->getMoveableType()==Moveable::MOV_PROJECTILE)
{ // 2.2 projectile hits kart
// -------------------------
Projectile *p=(Projectile*)movB;
p->explode((Kart*)movA);
}
else if(movB->getMoveableType()==Moveable::MOV_KART)
{ // 2.3 kart hits kart
// ------------------
Kart *kartA = (Kart*)movA;
Kart *kartB = (Kart*)movB;
// First check for bomb attachments
Attachment *attachmentA=kartA->getAttachment();
if(attachmentA->getType()==ATTACH_BOMB &&
attachmentA->getPreviousOwner()!=kartB)
{
attachmentA->moveBombFromTo(kartA, kartB);
}
Attachment *attachmentB=kartB->getAttachment();
if(attachmentB->getType()==ATTACH_BOMB &&
attachmentB->getPreviousOwner()!=kartA)
{
attachmentB->moveBombFromTo(kartB, kartA);
}
if(kartA->isPlayerKart()) sound_manager->playSfx(SOUND_CRASH);
if(kartB->isPlayerKart()) sound_manager->playSfx(SOUND_CRASH);
}
}
// 3) object is a projectile
// ========================
else if(movA->getMoveableType()==Moveable::MOV_PROJECTILE)
{
if(!movB)
{ // 3.1) projectile hits track
// --------------------------
((Projectile*)movA)->explode(NULL);
}
else if(movB->getMoveableType()==Moveable::MOV_PROJECTILE)
{ // 3.2 projectile hits projectile
// ------------------------------
((Projectile*)movA)->explode(NULL);
((Projectile*)movB)->explode(NULL);
}
else if(movB->getMoveableType()==Moveable::MOV_KART)
{ // 3.3 projectile hits kart
// ------------------------
Projectile *p=(Projectile*)movA;
p->explode((Kart*)movB);
}
}
// 4) Nothing else should happen
// =============================
else
{
assert("Unknown user pointer");
}
} // for i<numManifolds
} // handleCollisions
// -----------------------------------------------------------------------------
float Physics::getHOT(btVector3 pos)
{
btVector3 to_pos(pos);
to_pos.setZ(-100000.f);
btCollisionWorld::ClosestRayResultCallback
rayCallback(pos, to_pos);
m_dynamics_world->rayTest(pos, to_pos, rayCallback);
if(!rayCallback.HasHit()) return NOHIT;
return 1.0f;
} // getHOT
// -----------------------------------------------------------------------------
bool Physics::getTerrainNormal(btVector3 pos, btVector3* normal)
{
btVector3 to_pos(pos);
to_pos.setZ(-100000.f);
btCollisionWorld::ClosestRayResultCallback
rayCallback(pos, to_pos);
m_dynamics_world->rayTest(pos, to_pos, rayCallback);
if(!rayCallback.HasHit()) return false;
*normal = rayCallback.m_hitNormalWorld;
normal->normalize();
return true;
} // getTerrainNormal
// -----------------------------------------------------------------------------
//*
void Physics::draw()
@ -186,8 +318,6 @@ void Physics::draw()
btCollisionObject *obj = m_dynamics_world->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if(!body) continue;
//const btVector3 &pos=body->getCenterOfMassPosition();
//printf("body %d: %f %f %f dt %f\n",i, pos.x(), pos.y(), pos.z(),dt);
float m[16];
btVector3 wireColor(1,0,0);
btDefaultMotionState *myMotion = (btDefaultMotionState*)body->getMotionState();

View File

@ -25,27 +25,34 @@
#ifdef BULLET
#include "btBulletDynamicsCommon.h"
#include "../bullet/Demos/OpenGL/GLDebugDrawer.h"
#include "bullet/Demos/OpenGL/GLDebugDrawer.h"
class Physics
{
protected:
btDynamicsWorld *m_dynamics_world;
Kart *m_kart;
GLDebugDrawer *m_debug_drawer;
btDynamicsWorld *m_dynamics_world;
Kart *m_kart;
GLDebugDrawer *m_debug_drawer;
btCollisionDispatcher *m_dispatcher;
void convertTrack(ssgEntity *track, sgMat4 m);
void convertTrack(ssgEntity *track, sgMat4 m, btTriangleMesh* track_mesh);
public:
Physics (float gravity);
~Physics ();
void addKart (const Kart *k, btRaycastVehicle *v);
void removeKart (const Kart *k, btRaycastVehicle *v);
void update (float dt);
void draw ();
void setTrack (ssgEntity *track);
btDynamicsWorld *getPhysicsWorld() const {return m_dynamics_world;}
void debugDraw (float m[16], btCollisionShape *s, const btVector3 color);
Physics (float gravity);
~Physics ();
void addKart (const Kart *k, btRaycastVehicle *v);
void addBody (btRigidBody* b) {m_dynamics_world->addRigidBody(b);}
void removeKart (const Kart *k);
void removeBody (btRigidBody* b) {m_dynamics_world->removeRigidBody(b);}
void update (float dt);
void handleCollisions();
void draw ();
void setTrack (ssgEntity *track);
btDynamicsWorld*
getPhysicsWorld () const {return m_dynamics_world;}
void debugDraw (float m[16], btCollisionShape *s, const btVector3 color);
static float NOHIT;
float getHOT (btVector3 pos);
bool getTerrainNormal(btVector3 pos, btVector3* normal);
};
// For non-bullet version: empty object
#else
class Physics

View File

@ -1,3 +1,4 @@
// $Id$
//
// SuperTuxKart - a fun racing game with go-kart
@ -25,11 +26,11 @@
#include "projectile_manager.hpp"
#include "sound_manager.hpp"
#include "scene.hpp"
#include "ssg_help.hpp"
Projectile::Projectile(Kart *kart, int collectable) : Moveable(false)
{
init(kart, collectable);
getModel()->clrTraversalMaskBits(SSGTRAV_ISECT|SSGTRAV_HOT);
} // Projectile
//-----------------------------------------------------------------------------
@ -37,17 +38,86 @@ void Projectile::init(Kart *kart, int collectable_)
{
m_owner = kart;
m_type = collectable_;
m_has_hit_something = false;
m_last_radar_beep = -1;
m_has_hit_something = false;
m_last_radar_beep = -1;
m_speed = collectable_manager->getSpeed(m_type);
ssgTransform *m = getModel();
ssgTransform *m = getModel();
m->addKid(collectable_manager->getModel(m_type));
scene->add(m);
#ifdef BULLET
m_exploded = false;
float x_min, x_max, y_min, y_max, z_min, z_max;
// getModel returns the transform node, so get the actual model node
MinMax(getModel()->getKid(0), &x_min, &x_max, &y_min, &y_max, &z_min, &z_max);
float half_length = 0.5f*(y_max-y_min);
btCylinderShape* shape = new btCylinderShapeX(btVector3(half_length,
0.5f*(z_max-z_min),
0.5f*(x_max-x_min)));
// The rocket has to start ahead of the kart (not in), so it has to
// be moved forward by (at least) half a kart lengt .. we use one length here
btTransform trans;
kart->getTrans(&trans);
// We should get heading from the kart, and pitch/roll from the terrain here
btVector3 normal;
if(world->getPhysics()->getTerrainNormal(trans.getOrigin(), &normal))
{
float m[4][4];
trans.getOpenGLMatrix((float*)&m);
sgCoord pos;
sgSetCoord(&pos, m);
btQuaternion q=trans.getRotation();
const float angle_terrain = DEGREE_TO_RAD(pos.hpr[0]);
// The projectile should have the pitch of the terrain on which the kart
// is - while this is not really realistic, it plays much better this way
const float X = -sin(angle_terrain);
const float Y = cos(angle_terrain);
// Compute the angle between the normal of the plane and the line to
// (x,y,0). (x,y,0) is normalised, so are the coordinates of the plane,
// simplifying the computation of the scalar product.
float pitch = ( normal.getX()*X + normal.getY()*Y ); // use ( x,y,0)
// The actual angle computed above is between the normal and the (x,y,0)
// line, so to compute the actual angles 90 degrees must be subtracted.
pos.hpr[1] = acosf(pitch)/M_PI*180.0f-90.0f;
btQuaternion r=trans.getRotation();
r.setEuler(DEGREE_TO_RAD(pos.hpr[1]),DEGREE_TO_RAD(pos.hpr[2]),DEGREE_TO_RAD(pos.hpr[0]));
trans.setRotation(r);
} // if a normal exist
m_initial_velocity = trans.getBasis()*btVector3(0.0f, m_speed, 0.0f);
btTransform offset;
offset.setOrigin(btVector3(0.0f, 2.0f*kart->getKartLength()+2.0f*half_length,
kart->getKartHeight()));
// The cylinder needs to be rotated by 90 degrees to face in the right direction:
btQuaternion r90(0.0f, 0.0f, -NINETY_DEGREE_RAD);
offset.setRotation(r90);
// Apply rotation and offste
trans *= offset;
float mass=1.0f;
createBody(mass, trans, shape, Moveable::MOV_PROJECTILE);
// Simplified rockets: no gravity
world->getPhysics()->addBody(getBody());
m_body->setGravity(btVector3(0.0f, 0.0f, 0.0f));
m_body->setLinearVelocity(m_initial_velocity);
// FIXME: for now it is necessary to synch the graphical position with the
// physical position, since 'hot' computation is done using the
// graphical position (and hot can trigger an explosion when no
// terrain is under the rocket). Once hot is done with bullet as
// well, this shouldn't be necessary anymore.
placeModel();
#else
sgCoord c;
sgCopyCoord(&c, kart->getCoord());
const float angle_terrain = c.hpr[0]*M_PI/180.0f;
// The projectile should have the pitch of the terrain on which the kart
// is - while this is not really realistic, it plays much better this way
const sgVec4* normal = kart->getNormalHOT();
if(normal)
{
@ -64,7 +134,7 @@ void Projectile::init(Kart *kart, int collectable_)
}
setCoord(&c);
scene->add(m);
#endif
} // init
//-----------------------------------------------------------------------------
@ -74,14 +144,39 @@ Projectile::~Projectile()
//-----------------------------------------------------------------------------
void Projectile::update (float dt)
{
#ifdef BULLET
if(m_exploded) return;
m_body->setLinearVelocity(m_initial_velocity);
#else
// we don't even do any physics here - just set the
// velocity, and ignore everything else for projectiles.
m_velocity.xyz[1] = m_speed;
sgCopyCoord ( &m_last_pos, &m_curr_pos);
#endif
Moveable::update(dt);
doObjectInteractions();
} // update
// -----------------------------------------------------------------------------
#ifdef BULLET
void Projectile::placeModel()
{
btTransform t;
getTrans(&t);
// FIXME: this 90 degrees rotation can be removed
// if the 3d model is rotated instead
btQuaternion r90(0.0f, 0.0f, NINETY_DEGREE_RAD);
t.setRotation(t.getRotation()*r90);
float m[4][4];
t.getOpenGLMatrix((float*)&m);
sgSetCoord(&m_curr_pos, m);
const btVector3 &v=m_body->getLinearVelocity();
sgSetVec3(m_velocity.xyz, v.x(), v.y(), v.z());
m_model->setTransform(&m_curr_pos);
} // placeModel
#endif
// -----------------------------------------------------------------------------
/** Returns true if this missile has hit something, otherwise false. */
void Projectile::doObjectInteractions ()
{
@ -98,13 +193,15 @@ void Projectile::doObjectInteractions ()
if ( m_type != COLLECT_NOTHING && kart != m_owner )
{
const float D = sgDistanceSquaredVec3 ( pos->xyz, getCoord()->xyz ) ;
#ifndef BULLET
if ( D < 2.0f )
{
explode(kart);
return;
}
else if ( D < ndist )
else
#endif
if ( D < ndist )
{
ndist = D ;
nearest = i ;
@ -175,6 +272,7 @@ void Projectile::doObjectInteractions ()
} // doObjectInteractions
//-----------------------------------------------------------------------------
#ifndef BULLET
void Projectile::doCollisionAnalysis ( float dt, float hot )
{
if ( m_collided || m_crashed )
@ -196,11 +294,15 @@ void Projectile::doCollisionAnalysis ( float dt, float hot )
}
} // if m_collided||m_crashed
} // doCollisionAnalysis
#endif
//-----------------------------------------------------------------------------
void Projectile::explode(Kart *kart_hit)
{
m_has_hit_something=true;
#ifdef BULLET
if(m_exploded) return;
#endif
m_has_hit_something=true;
m_curr_pos.xyz[2] += 1.2f ;
// Notify the projectile manager that this rocket has hit something.
// The manager will create the appropriate explosion object, and
@ -213,6 +315,10 @@ void Projectile::explode(Kart *kart_hit)
m->removeAllKids();
scene->remove(m);
#ifdef BULLET
world->getPhysics()->removeBody(getBody());
m_exploded=true;
#endif
for ( unsigned int i = 0 ; i < world->getNumKarts() ; i++ )
{
Kart *kart = world -> getKart(i);

View File

@ -33,13 +33,22 @@ class Projectile : public Moveable
int m_type ;
bool m_has_hit_something;
int m_last_radar_beep;
#ifdef BULLET
bool m_exploded;
btVector3 m_initial_velocity;
#endif
public:
Projectile (Kart* kart_, int type);
virtual ~Projectile();
void init (Kart* kart_, int type);
void update (float);
#ifdef BULLET
void placeModel ();
#endif
#ifndef BULLET
void doCollisionAnalysis (float dt, float hot);
#endif
void doObjectInteractions();
void explode (Kart* kart);
bool hasHit () {return m_has_hit_something;}

View File

@ -79,7 +79,6 @@ void ProjectileManager::cleanup()
/** General projectile update call. */
void ProjectileManager::update(float dt)
{
m_something_was_hit=false;
// First update all projectiles on the track
for(Projectiles::iterator i = m_active_projectiles.begin();
i != m_active_projectiles.end(); ++i)
@ -120,7 +119,7 @@ void ProjectileManager::update(float dt)
e=m_active_explosions.erase(e);
} // while e!=m_active_explosions.end()
} // if m_explosion_ended
m_something_was_hit=false;
} // update
// -----------------------------------------------------------------------------

View File

@ -55,7 +55,7 @@ private:
bool m_explosion_ended;
public:
ProjectileManager() {};
ProjectileManager() {m_something_was_hit=false;};
~ProjectileManager() {};
void explode () {m_something_was_hit=true;}
void FinishedExplosion() {m_explosion_ended =true;}

View File

@ -124,7 +124,7 @@ World::World(const RaceSetup& raceSetup_) : m_race_setup(raceSetup_)
{
// In profile mode, load only the old kart
newkart = new DefaultRobot (kart_properties_manager->getKart("tuxkart"), pos,
init_pos);
init_pos);
}
else
{
@ -142,7 +142,7 @@ World::World(const RaceSetup& raceSetup_) : m_race_setup(raceSetup_)
else
{
newkart = loadRobot(kart_properties_manager->getKart(*i), pos,
init_pos);
init_pos);
}
} // if !user_config->m_profile
if(user_config->m_replay_history)
@ -193,13 +193,13 @@ World::World(const RaceSetup& raceSetup_) : m_race_setup(raceSetup_)
#ifdef HAVE_GHOST_REPLAY
m_replay_recorder.initRecorder( m_race_setup.getNumKarts() );
m_p_replay_player = new ReplayPlayer;
m_p_replay_player = new ReplayPlayer;
if( !loadReplayHumanReadable( "test1" ) )
{
delete m_p_replay_player;
m_p_replay_player = NULL;
}
if( m_p_replay_player ) m_p_replay_player->showReplayAt( 0.0 );
{
delete m_p_replay_player;
m_p_replay_player = NULL;
}
if( m_p_replay_player ) m_p_replay_player->showReplayAt( 0.0 );
#endif
}
@ -234,14 +234,14 @@ World::~World()
#ifdef HAVE_GHOST_REPLAY
m_replay_recorder.destroy();
if( m_p_replay_player )
{
m_p_replay_player->destroy();
delete m_p_replay_player;
m_p_replay_player = NULL;
}
if( m_p_replay_player )
{
m_p_replay_player->destroy();
delete m_p_replay_player;
m_p_replay_player = NULL;
}
#endif
}
} // ~World
//-----------------------------------------------------------------------------
/** Waits till each kart is resting on the ground
@ -281,11 +281,11 @@ void World::update(float delta)
if(user_config->m_replay_history) delta=history->GetNextDelta();
checkRaceStatus();
// this line was before checkRaceStatus. but m_clock is set to 0.0 in
// checkRaceStatus on start, so m_clock would not be synchron and the
// first delta would not be added .. that would cause a gap in
// replay-recording
m_clock += delta;
// this line was before checkRaceStatus. but m_clock is set to 0.0 in
// checkRaceStatus on start, so m_clock would not be synchron and the
// first delta would not be added .. that would cause a gap in
// replay-recording
m_clock += delta;
// Count the number of collision in the next 'FRAMES_FOR_TRAFFIC_JAM' frames.
// If a kart has more than one hit, play 'traffic jam' noise.
@ -312,7 +312,7 @@ void World::update(float delta)
// Don't record the time for the last kart, since it didn't finish
// the race - unless it's timetrial (then there is only one kart)
unsigned int karts_to_enter = (m_race_setup.m_mode==RaceSetup::RM_TIME_TRIAL)
unsigned int karts_to_enter = (m_race_setup.m_mode==RaceSetup::RM_TIME_TRIAL)
? m_kart.size() : m_kart.size()-1;
for(unsigned int pos=0; pos<karts_to_enter; pos++)
{
@ -325,12 +325,12 @@ void World::update(float delta)
? Highscores::HST_TIMETRIAL_OVERALL_TIME
: Highscores::HST_RACE_OVERALL_TIME;
if(m_highscores->addData(hst, m_kart.size(),
m_race_setup.m_difficulty,
m_track->getName(),
k->getName(),
k->getPlayer()->getName(),
k->getFinishTime(),
m_race_setup.m_num_laps)>0)
m_race_setup.m_difficulty,
m_track->getName(),
k->getName(),
k->getPlayer()->getName(),
k->getFinishTime(),
m_race_setup.m_num_laps)>0)
{
highscore_manager->Save();
}
@ -391,13 +391,13 @@ void World::update(float delta)
}
#ifdef HAVE_GHOST_REPLAY
// we start recording after START_PHASE, since during start-phase m_clock is incremented
// normally, but after switching to RACE_PHASE m_clock is set back to 0.0
if( m_phase != START_PHASE )
{
m_replay_recorder.pushFrame();
if( m_p_replay_player ) m_p_replay_player->showReplayAt( m_clock );
}
// we start recording after START_PHASE, since during start-phase m_clock is incremented
// normally, but after switching to RACE_PHASE m_clock is set back to 0.0
if( m_phase != START_PHASE )
{
m_replay_recorder.pushFrame();
if( m_p_replay_player ) m_p_replay_player->showReplayAt( m_clock );
}
#endif
}
@ -504,8 +504,8 @@ void World::checkRaceStatus()
m_clock = 0.0f;
sound_manager->playSfx(SOUND_START);
#ifdef HAVE_GHOST_REPLAY
// push positions at time 0.0 to replay-data
m_replay_recorder.pushFrame();
// push positions at time 0.0 to replay-data
m_replay_recorder.pushFrame();
#endif
}
else if (m_clock > 1.0 && m_ready_set_go == 2)
@ -858,7 +858,7 @@ void World::restartRace()
m_replay_recorder.destroy();
m_replay_recorder.initRecorder( m_race_setup.getNumKarts() );
if( m_p_replay_player )
if( m_p_replay_player )
{
m_p_replay_player->reset();
m_p_replay_player->showReplayAt( 0.0 );
@ -874,7 +874,7 @@ Kart* World::loadRobot(const KartProperties *kart_properties, int position,
const int NUM_ROBOTS = 1;
srand((unsigned)std::time(0));
srand((unsigned)std::time(0));
switch(rand() % NUM_ROBOTS)
{