Made Physics a singleton, removing the accessor functions from World.

Removes dependency on World for a few files.
This commit is contained in:
hiker 2016-12-13 08:31:08 +11:00
parent cd149ab5d7
commit b12453e9ca
21 changed files with 70 additions and 68 deletions

View File

@ -71,7 +71,7 @@ void FixedPipelineRenderer::render(float dt)
// is not set up properly. This is only used for // is not set up properly. This is only used for
// the bullet debug view. // the bullet debug view.
if (UserConfigParams::m_artist_debug_mode) if (UserConfigParams::m_artist_debug_mode)
World::getWorld()->getPhysics()->draw(); Physics::getInstance()->draw();
} // for i<world->getNumKarts() } // for i<world->getNumKarts()
// Set the viewport back to the full screen for race gui // Set the viewport back to the full screen for race gui

View File

@ -2078,9 +2078,9 @@ void IrrDriver::update(float dt)
GUIEngine::render(dt); GUIEngine::render(dt);
} }
if (world->getPhysics() != NULL) if (Physics::getInstance())
{ {
IrrDebugDrawer* debug_drawer = world->getPhysics()->getDebugDrawer(); IrrDebugDrawer* debug_drawer = Physics::getInstance()->getDebugDrawer();
if (debug_drawer != NULL && debug_drawer->debugEnabled()) if (debug_drawer != NULL && debug_drawer->debugEnabled())
{ {
debug_drawer->beginNextFrame(); debug_drawer->beginNextFrame();

View File

@ -1436,7 +1436,7 @@ FrameBuffer *PostProcessing::render(scene::ICameraSceneNode * const camnode,
glDisable(GL_BLEND); glDisable(GL_BLEND);
World *world = World::getWorld(); World *world = World::getWorld();
Physics *physics = world ? world->getPhysics() : NULL; Physics *physics = Physics::getInstance();
if (isRace && UserConfigParams::m_dof && (physics == NULL || !physics->isDebug())) if (isRace && UserConfigParams::m_dof && (physics == NULL || !physics->isDebug()))
{ {

View File

@ -547,15 +547,16 @@ void ShaderBasedRenderer::debugPhysics()
// the bullet debug view, since otherwise the camera // the bullet debug view, since otherwise the camera
// is not set up properly. This is only used for // is not set up properly. This is only used for
// the bullet debug view. // the bullet debug view.
World *world = World::getWorld(); if(Physics::getInstance())
if (UserConfigParams::m_artist_debug_mode)
world->getPhysics()->draw();
if (world != NULL && world->getPhysics() != NULL)
{ {
IrrDebugDrawer* debug_drawer = world->getPhysics()->getDebugDrawer(); if (UserConfigParams::m_artist_debug_mode)
Physics::getInstance()->draw();
IrrDebugDrawer* debug_drawer = Physics::getInstance()->getDebugDrawer();
if (debug_drawer != NULL && debug_drawer->debugEnabled()) if (debug_drawer != NULL && debug_drawer->debugEnabled())
{ {
const std::map<video::SColor, std::vector<float> >& lines = debug_drawer->getLines(); const std::map<video::SColor, std::vector<float> >& lines =
debug_drawer->getLines();
std::map<video::SColor, std::vector<float> >::const_iterator it; std::map<video::SColor, std::vector<float> >::const_iterator it;
Shaders::ColoredLine *line = Shaders::ColoredLine::getInstance(); Shaders::ColoredLine *line = Shaders::ColoredLine::getInstance();

View File

@ -133,7 +133,7 @@ void Flyable::createPhysics(float forw_offset, const Vec3 &velocity,
m_shape = shape; m_shape = shape;
createBody(m_mass, trans, m_shape, restitution); createBody(m_mass, trans, m_shape, restitution);
m_user_pointer.set(this); m_user_pointer.set(this);
World::getWorld()->getPhysics()->addBody(getBody()); Physics::getInstance()->addBody(getBody());
m_body->setGravity(gravity); m_body->setGravity(gravity);
@ -199,7 +199,7 @@ void Flyable::init(const XMLNode &node, scene::IMesh *model,
Flyable::~Flyable() Flyable::~Flyable()
{ {
if(m_shape) delete m_shape; if(m_shape) delete m_shape;
World::getWorld()->getPhysics()->removeBody(getBody()); Physics::getInstance()->removeBody(getBody());
} // ~Flyable } // ~Flyable
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------

View File

@ -28,7 +28,6 @@
#include "karts/abstract_kart.hpp" #include "karts/abstract_kart.hpp"
#include "karts/controller/controller.hpp" #include "karts/controller/controller.hpp"
#include "karts/kart_properties.hpp" #include "karts/kart_properties.hpp"
#include "modes/world.hpp"
#include "physics/physical_object.hpp" #include "physics/physical_object.hpp"
#include "physics/physics.hpp" #include "physics/physics.hpp"
#include "tracks/track.hpp" #include "tracks/track.hpp"
@ -174,7 +173,7 @@ bool Plunger::hit(AbstractKart *kart, PhysicalObject *obj)
m_keep_alive = 0; m_keep_alive = 0;
// Make this object invisible. // Make this object invisible.
getNode()->setVisible(false); getNode()->setVisible(false);
World::getWorld()->getPhysics()->removeBody(getBody()); Physics::getInstance()->removeBody(getBody());
} }
else else
{ {
@ -188,7 +187,7 @@ bool Plunger::hit(AbstractKart *kart, PhysicalObject *obj)
{ {
node->setVisible(false); node->setVisible(false);
} }
World::getWorld()->getPhysics()->removeBody(getBody()); Physics::getInstance()->removeBody(getBody());
if(kart) if(kart)
{ {

View File

@ -29,7 +29,6 @@
#include "karts/abstract_kart.hpp" #include "karts/abstract_kart.hpp"
#include "karts/kart_properties.hpp" #include "karts/kart_properties.hpp"
#include "karts/max_speed.hpp" #include "karts/max_speed.hpp"
#include "modes/world.hpp"
#include "physics/physics.hpp" #include "physics/physics.hpp"
#include "race/race_manager.hpp" #include "race/race_manager.hpp"
#include "utils/string_utils.hpp" #include "utils/string_utils.hpp"
@ -215,8 +214,7 @@ void RubberBand::checkForHit(const Vec3 &k, const Vec3 &p)
m_owner->getBody()->getBroadphaseHandle()->m_collisionFilterGroup = 0; m_owner->getBody()->getBroadphaseHandle()->m_collisionFilterGroup = 0;
// Do the raycast // Do the raycast
World::getWorld()->getPhysics()->getPhysicsWorld()->rayTest(k, p, Physics::getInstance()->getPhysicsWorld()->rayTest(k, p, ray_callback);
ray_callback);
// Reset collision groups // Reset collision groups
m_plunger->getBody()->getBroadphaseHandle()->m_collisionFilterGroup = old_plunger_group; m_plunger->getBody()->getBroadphaseHandle()->m_collisionFilterGroup = old_plunger_group;
if(m_owner->getBody()->getBroadphaseHandle()) if(m_owner->getBody()->getBroadphaseHandle())

View File

@ -22,7 +22,6 @@
#include "karts/abstract_kart.hpp" #include "karts/abstract_kart.hpp"
#include "karts/kart_model.hpp" #include "karts/kart_model.hpp"
#include "karts/skidding.hpp" #include "karts/skidding.hpp"
#include "modes/world.hpp"
#include "physics/physics.hpp" #include "physics/physics.hpp"
AbstractKartAnimation::AbstractKartAnimation(AbstractKart *kart, AbstractKartAnimation::AbstractKartAnimation(AbstractKart *kart,
@ -48,7 +47,7 @@ AbstractKartAnimation::AbstractKartAnimation(AbstractKart *kart,
// Register this animation with the kart (which will free it // Register this animation with the kart (which will free it
// later). // later).
kart->setKartAnimation(this); kart->setKartAnimation(this);
World::getWorld()->getPhysics()->removeKart(m_kart); Physics::getInstance()->removeKart(m_kart);
kart->getSkidding()->reset(); kart->getSkidding()->reset();
kart->getSlipstream()->reset(); kart->getSlipstream()->reset();
if(kart->isSquashed()) if(kart->isSquashed())
@ -74,7 +73,7 @@ AbstractKartAnimation::~AbstractKartAnimation()
if(m_timer < 0) if(m_timer < 0)
{ {
m_kart->getBody()->setAngularVelocity(btVector3(0,0,0)); m_kart->getBody()->setAngularVelocity(btVector3(0,0,0));
World::getWorld()->getPhysics()->addKart(m_kart); Physics::getInstance()->addKart(m_kart);
} }
} // ~AbstractKartAnimation } // ~AbstractKartAnimation

View File

@ -113,7 +113,7 @@ void SpareTireAI::spawn(float time_to_last)
findDefaultPath(); findDefaultPath();
m_timer = time_to_last; m_timer = time_to_last;
World::getWorld()->getPhysics()->addKart(m_kart); Physics::getInstance()->addKart(m_kart);
m_kart->startEngineSFX(); m_kart->startEngineSFX();
m_kart->getKartGFX()->reset(); m_kart->getKartGFX()->reset();
m_kart->getNode()->setVisible(true); m_kart->getNode()->setVisible(true);

View File

@ -273,7 +273,7 @@ Kart::~Kart()
// Ghost karts don't have a body // Ghost karts don't have a body
if(m_body) if(m_body)
{ {
World::getWorld()->getPhysics()->removeKart(this); Physics::getInstance()->removeKart(this);
delete m_vehicle; delete m_vehicle;
delete m_vehicle_raycaster; delete m_vehicle_raycaster;
} }
@ -310,8 +310,8 @@ void Kart::reset()
// don't have one). // don't have one).
if(m_body) if(m_body)
{ {
World::getWorld()->getPhysics()->removeKart(this); Physics::getInstance()->removeKart(this);
World::getWorld()->getPhysics()->addKart(this); Physics::getInstance()->addKart(this);
} }
m_min_nitro_time = 0.0f; m_min_nitro_time = 0.0f;
@ -671,7 +671,7 @@ void Kart::createPhysics()
// Create the actual vehicle // Create the actual vehicle
// ------------------------- // -------------------------
m_vehicle_raycaster = m_vehicle_raycaster =
new btKartRaycaster(World::getWorld()->getPhysics()->getPhysicsWorld(), new btKartRaycaster(Physics::getInstance()->getPhysicsWorld(),
stk_config->m_smooth_normals && stk_config->m_smooth_normals &&
Track::getCurrentTrack()->smoothNormals()); Track::getCurrentTrack()->smoothNormals());
m_vehicle = new btKart(m_body, m_vehicle_raycaster, this); m_vehicle = new btKart(m_body, m_vehicle_raycaster, this);
@ -1158,7 +1158,7 @@ void Kart::eliminate()
{ {
if (!getKartAnimation()) if (!getKartAnimation())
{ {
World::getWorld()->getPhysics()->removeKart(this); Physics::getInstance()->removeKart(this);
} }
if (m_stars_effect) if (m_stars_effect)
{ {

View File

@ -89,7 +89,7 @@ RescueAnimation::~RescueAnimation()
{ {
m_kart->getBody()->setLinearVelocity(btVector3(0,0,0)); m_kart->getBody()->setLinearVelocity(btVector3(0,0,0));
m_kart->getBody()->setAngularVelocity(btVector3(0,0,0)); m_kart->getBody()->setAngularVelocity(btVector3(0,0,0));
World::getWorld()->getPhysics()->addKart(m_kart); Physics::getInstance()->addKart(m_kart);
for(unsigned int i=0; i<Camera::getNumCameras(); i++) for(unsigned int i=0; i<Camera::getNumCameras(); i++)
{ {
Camera *camera = Camera::getCamera(i); Camera *camera = Camera::getCamera(i);

View File

@ -121,7 +121,6 @@ World::World() : WorldStatus()
m_magic_number = 0xB01D6543; m_magic_number = 0xB01D6543;
#endif #endif
m_physics = NULL;
m_race_gui = NULL; m_race_gui = NULL;
m_saved_race_gui = NULL; m_saved_race_gui = NULL;
m_use_highscores = true; m_use_highscores = true;
@ -181,7 +180,7 @@ void World::init()
m_script_engine->loadScript(script_path, true); m_script_engine->loadScript(script_path, true);
// Create the physics // Create the physics
m_physics = new Physics(); Physics::getInstance<Physics>();
unsigned int num_karts = race_manager->getNumberOfKarts(); unsigned int num_karts = race_manager->getNumberOfKarts();
//assert(num_karts > 0); //assert(num_karts > 0);
@ -489,9 +488,10 @@ World::~World()
Camera::removeAllCameras(); Camera::removeAllCameras();
projectile_manager->cleanup(); projectile_manager->cleanup();
// In case that the track is not found, m_physics is still undefined.
if(m_physics) // In case that the track is not found, Physics was not instantiated,
delete m_physics; // but kill handles this correctly.
Physics::kill();
delete m_script_engine; delete m_script_engine;
@ -654,7 +654,7 @@ void World::resetAllKarts()
{ {
// Reset the physics 'remaining' time to 0 so that the number // Reset the physics 'remaining' time to 0 so that the number
// of timesteps is reproducible if doing a physics-based history run // of timesteps is reproducible if doing a physics-based history run
getPhysics()->getPhysicsWorld()->resetLocalTime(); Physics::getInstance()->getPhysicsWorld()->resetLocalTime();
// If track checking is requested, check all rescue positions if // If track checking is requested, check all rescue positions if
// they are high enough. // they are high enough.
@ -727,7 +727,7 @@ void World::resetAllKarts()
(*i)->getBody()->setGravity((*i)->getMaterial()->hasGravity() ? (*i)->getBody()->setGravity((*i)->getMaterial()->hasGravity() ?
(*i)->getNormal() * -g : Vec3(0, -g, 0)); (*i)->getNormal() * -g : Vec3(0, -g, 0));
} }
for(int i=0; i<60; i++) m_physics->update(1.f/60.f); for(int i=0; i<60; i++) Physics::getInstance()->update(1.f/60.f);
for ( KartList::iterator i=m_karts.begin(); i!=m_karts.end(); i++) for ( KartList::iterator i=m_karts.begin(); i!=m_karts.end(); i++)
{ {
@ -1002,7 +1002,7 @@ void World::update(float dt)
if (!history->dontDoPhysics()) if (!history->dontDoPhysics())
{ {
m_physics->update(dt); Physics::getInstance()->update(dt);
} }
PROFILER_PUSH_CPU_MARKER("World::update (weather)", 0x80, 0x7F, 0x00); PROFILER_PUSH_CPU_MARKER("World::update (weather)", 0x80, 0x7F, 0x00);

View File

@ -41,7 +41,6 @@ class AbstractKart;
class btRigidBody; class btRigidBody;
class Controller; class Controller;
class PhysicalObject; class PhysicalObject;
class Physics;
namespace Scripting namespace Scripting
{ {
@ -95,7 +94,6 @@ protected:
KartList m_karts; KartList m_karts;
RandomGenerator m_random; RandomGenerator m_random;
Physics* m_physics;
AbstractKart* m_fastest_kart; AbstractKart* m_fastest_kart;
/** Number of eliminated karts. */ /** Number of eliminated karts. */
int m_eliminated_karts; int m_eliminated_karts;
@ -311,9 +309,6 @@ public:
unsigned int getCurrentNumPlayers() const { return m_num_players - unsigned int getCurrentNumPlayers() const { return m_num_players -
m_eliminated_players;} m_eliminated_players;}
// ------------------------------------------------------------------------ // ------------------------------------------------------------------------
/** Returns a pointer to the physics. */
Physics *getPhysics() const { return m_physics; }
// ------------------------------------------------------------------------
/** Returns a pointer to the Scripting Engine. */ /** Returns a pointer to the Scripting Engine. */
Scripting::ScriptEngine *getScriptEngine() Scripting::ScriptEngine *getScriptEngine()
const { return m_script_engine; } const { return m_script_engine; }

View File

@ -18,7 +18,6 @@
#include "network/rewind_info.hpp" #include "network/rewind_info.hpp"
#include "modes/world.hpp"
#include "physics/physics.hpp" #include "physics/physics.hpp"
/** Constructor for a state: it only takes the size, and allocates a buffer /** Constructor for a state: it only takes the size, and allocates a buffer
@ -42,8 +41,8 @@ RewindInfoState::RewindInfoState(float time, Rewinder *rewinder,
BareNetworkString *buffer, bool is_confirmed) BareNetworkString *buffer, bool is_confirmed)
: RewindInfoRewinder(time, rewinder, buffer, is_confirmed) : RewindInfoRewinder(time, rewinder, buffer, is_confirmed)
{ {
m_local_physics_time = World::getWorld()->getPhysics()->getPhysicsWorld() m_local_physics_time = Physics::getInstance()->getPhysicsWorld()
->getLocalTime(); ->getLocalTime();
} // RewindInfoState } // RewindInfoState
// ============================================================================ // ============================================================================

View File

@ -322,7 +322,7 @@ void RewindManager::rewindTo(float rewind_time)
// Now start the rewind with the full state: // Now start the rewind with the full state:
world->setTime(exact_rewind_time); world->setTime(exact_rewind_time);
float local_physics_time = state->getLocalPhysicsTime(); float local_physics_time = state->getLocalPhysicsTime();
world->getPhysics()->getPhysicsWorld()->setLocalTime(local_physics_time); Physics::getInstance()->getPhysicsWorld()->setLocalTime(local_physics_time);
// Restore all states from the current time - the full state of a race // Restore all states from the current time - the full state of a race
// will be potentially stored in several state objects. State can be NULL // will be potentially stored in several state objects. State can be NULL

View File

@ -18,18 +18,12 @@
#include "physics/physical_object.hpp" #include "physics/physical_object.hpp"
#include <memory> #include "config/stk_config.hpp"
#include <string>
#include <vector>
using namespace irr;
#include "graphics/material.hpp" #include "graphics/material.hpp"
#include "graphics/material_manager.hpp" #include "graphics/material_manager.hpp"
#include "graphics/mesh_tools.hpp" #include "graphics/mesh_tools.hpp"
#include "io/file_manager.hpp" #include "io/file_manager.hpp"
#include "io/xml_node.hpp" #include "io/xml_node.hpp"
#include "modes/world.hpp"
#include "physics/physics.hpp" #include "physics/physics.hpp"
#include "physics/triangle_mesh.hpp" #include "physics/triangle_mesh.hpp"
#include "tracks/track.hpp" #include "tracks/track.hpp"
@ -40,6 +34,11 @@ using namespace irr;
#include <ISceneManager.h> #include <ISceneManager.h>
#include <IMeshSceneNode.h> #include <IMeshSceneNode.h>
#include <ITexture.h> #include <ITexture.h>
using namespace irr;
#include <memory>
#include <string>
#include <vector>
/** Creates a physical Settings object with the given type, radius and mass. /** Creates a physical Settings object with the given type, radius and mass.
*/ */
@ -180,7 +179,7 @@ PhysicalObject::PhysicalObject(bool is_dynamic,
// ---------------------------------------------------------------------------- // ----------------------------------------------------------------------------
PhysicalObject::~PhysicalObject() PhysicalObject::~PhysicalObject()
{ {
World::getWorld()->getPhysics()->removeBody(m_body); Physics::getInstance()->removeBody(m_body);
delete m_body; delete m_body;
delete m_motion_state; delete m_motion_state;
@ -540,7 +539,7 @@ void PhysicalObject::init(const PhysicalObject::Settings& settings)
m_body->setActivationState(DISABLE_DEACTIVATION); m_body->setActivationState(DISABLE_DEACTIVATION);
} }
World::getWorld()->getPhysics()->addBody(m_body); Physics::getInstance()->addBody(m_body);
m_body_added = true; m_body_added = true;
if(m_triangle_mesh) if(m_triangle_mesh)
m_triangle_mesh->setBody(m_body); m_triangle_mesh->setBody(m_body);
@ -672,7 +671,7 @@ void PhysicalObject::removeBody()
{ {
if (m_body_added) if (m_body_added)
{ {
World::getWorld()->getPhysics()->removeBody(m_body); Physics::getInstance()->removeBody(m_body);
m_body_added = false; m_body_added = false;
} }
} // Remove body } // Remove body
@ -684,7 +683,7 @@ void PhysicalObject::addBody()
if (!m_body_added) if (!m_body_added)
{ {
m_body_added = true; m_body_added = true;
World::getWorld()->getPhysics()->addBody(m_body); Physics::getInstance()->addBody(m_body);
} }
} // Add body } // Add body

View File

@ -32,6 +32,7 @@
#include "physics/irr_debug_drawer.hpp" #include "physics/irr_debug_drawer.hpp"
#include "physics/stk_dynamics_world.hpp" #include "physics/stk_dynamics_world.hpp"
#include "physics/user_pointer.hpp" #include "physics/user_pointer.hpp"
#include "utils/singleton.hpp"
class AbstractKart; class AbstractKart;
class STKDynamicsWorld; class STKDynamicsWorld;
@ -41,6 +42,7 @@ class Vec3;
* \ingroup physics * \ingroup physics
*/ */
class Physics : public btSequentialImpulseConstraintSolver class Physics : public btSequentialImpulseConstraintSolver
, public AbstractSingleton<Physics>
{ {
private: private:
/** Bullet can report the same collision more than once (up to 4 /** Bullet can report the same collision more than once (up to 4
@ -53,7 +55,8 @@ private:
* overhead (since it will likely use a tree to sort the entries). * overhead (since it will likely use a tree to sort the entries).
* Considering that the number of collisions is usually rather small * Considering that the number of collisions is usually rather small
* a simple list and linear search is faster is is being used here. */ * a simple list and linear search is faster is is being used here. */
class CollisionPair { class CollisionPair
{
private: private:
/** The user pointer of the objects involved in this collision. */ /** The user pointer of the objects involved in this collision. */
const UserPointer *m_up[2]; const UserPointer *m_up[2];
@ -140,14 +143,19 @@ private:
/** Used in physics debugging to draw the physics world. */ /** Used in physics debugging to draw the physics world. */
IrrDebugDrawer *m_debug_drawer; IrrDebugDrawer *m_debug_drawer;
btCollisionDispatcher *m_dispatcher; btCollisionDispatcher *m_dispatcher;
btBroadphaseInterface *m_axis_sweep; btBroadphaseInterface *m_axis_sweep;
btDefaultCollisionConfiguration *m_collision_conf; btDefaultCollisionConfiguration *m_collision_conf;
CollisionList m_all_collisions; CollisionList m_all_collisions;
/** Singleton. */
static Physics *m_physics;
Physics();
virtual ~Physics();
friend class AbstractSingleton<Physics>;
public: public:
Physics ();
~Physics ();
void init (const Vec3 &min_world, const Vec3 &max_world); void init (const Vec3 &min_world, const Vec3 &max_world);
void addKart (const AbstractKart *k); void addKart (const AbstractKart *k);
void addBody (btRigidBody* b) {m_dynamics_world->addRigidBody(b);} void addBody (btRigidBody* b) {m_dynamics_world->addRigidBody(b);}

View File

@ -21,6 +21,10 @@
#include "btBulletDynamicsCommon.h" #include "btBulletDynamicsCommon.h"
/** A thin wrapper around bullet's btDiscreteDynamicsWorld. Used to
* be able to query and set the 'left over' time from a previous
* time step, which is needed for more precise rewind/replays.
*/
class STKDynamicsWorld : public btDiscreteDynamicsWorld class STKDynamicsWorld : public btDiscreteDynamicsWorld
{ {
public: public:

View File

@ -18,13 +18,13 @@
#include "physics/triangle_mesh.hpp" #include "physics/triangle_mesh.hpp"
#include "btBulletDynamicsCommon.h" #include "config/stk_config.hpp"
#include "modes/world.hpp"
#include "physics/physics.hpp" #include "physics/physics.hpp"
#include "utils/constants.hpp" #include "utils/constants.hpp"
#include "utils/time.hpp" #include "utils/time.hpp"
#include "btBulletDynamicsCommon.h"
#include <fstream> #include <fstream>
// ----------------------------------------------------------------------------- // -----------------------------------------------------------------------------
@ -190,7 +190,7 @@ void TriangleMesh::createPhysicalBody(btCollisionObject::CollisionFlags flags,
m_collision_shape); m_collision_shape);
info.m_restitution = 0.8f; info.m_restitution = 0.8f;
m_body=new btRigidBody(info); m_body=new btRigidBody(info);
World::getWorld()->getPhysics()->addBody(m_body); Physics::getInstance()->addBody(m_body);
m_body->setUserPointer(&m_user_pointer); m_body->setUserPointer(&m_user_pointer);
m_body->setCollisionFlags(m_body->getCollisionFlags() | m_body->setCollisionFlags(m_body->getCollisionFlags() |
@ -210,7 +210,7 @@ void TriangleMesh::removeAll()
// Don't free the physical body if it was created outside this object. // Don't free the physical body if it was created outside this object.
if(m_body && m_free_body) if(m_body && m_free_body)
{ {
World::getWorld()->getPhysics()->removeBody(m_body); Physics::getInstance()->removeBody(m_body);
delete m_body; delete m_body;
delete m_motion_state; delete m_motion_state;
m_body = NULL; m_body = NULL;

View File

@ -1183,7 +1183,7 @@ bool Track::loadMainTrack(const XMLNode &root)
// could be relaxed to fix this, it is not certain how the physics // could be relaxed to fix this, it is not certain how the physics
// will handle items that are out of the AABB // will handle items that are out of the AABB
m_aabb_max.setY(m_aabb_max.getY()+30.0f); m_aabb_max.setY(m_aabb_max.getY()+30.0f);
World::getWorld()->getPhysics()->init(m_aabb_min, m_aabb_max); Physics::getInstance()->init(m_aabb_min, m_aabb_max);
ModelDefinitionLoader lodLoader(this); ModelDefinitionLoader lodLoader(this);

View File

@ -230,7 +230,7 @@ bool handleContextMenuAction(s32 cmd_id)
{ {
World *world = World::getWorld(); World *world = World::getWorld();
Physics *physics = world ? world->getPhysics() : NULL; Physics *physics = Physics::getInstance();
switch(cmd_id) switch(cmd_id)
{ {
case DEBUG_GRAPHICS_RELOAD_SHADERS: case DEBUG_GRAPHICS_RELOAD_SHADERS:
@ -325,8 +325,8 @@ bool handleContextMenuAction(s32 cmd_id)
{ {
irr_driver->resetDebugModes(); irr_driver->resetDebugModes();
if (!world) return false; Physics *physics = Physics::getInstance();
Physics *physics = world->getPhysics(); if (!physics) return false;
physics->setDebugMode(IrrDebugDrawer::DM_NO_KARTS_GRAPHICS); physics->setDebugMode(IrrDebugDrawer::DM_NO_KARTS_GRAPHICS);
break; break;
} }