Newbie: stepSimulation does nothing

Physics APIs, Physics file formats, Maya, Max, XSI, Cinema 4D, Lightwave, Blender, thinkingParticles™ and other simulation tools, exporters and importers
Post Reply
Papierkorb
Posts: 1
Joined: Wed Jan 12, 2011 5:16 pm

Newbie: stepSimulation does nothing

Post by Papierkorb »

Hello,
I want to use Bullet in my game project.
The first thing i did was implementing the HelloWorld code in some function which is
often called (Quick n' dirty, just to test). This worked out pretty good for a "hack".
Next thing was of course implementing the complete necessary code in the engine
(I'm using OGRE3D for graphics). I've set up everything and I'm calling stepSimulation
after every frame (I had some output code, so the handler function is called). But
the function seems to do nothing at all. Via output I could see, that Bullet once
retrieves the position and rotation of new objects (getWorldTransform) but never
calls "setWorldTransform". I've also recently tried using btDefaultMotionState and
setting the new positions in a loop, but stepSimulation does nothing. So, after
trying about 4 days getting this to work, I have no clue what to do to get it to
work :/

Here are the code chunks that are doing something with Bullet:

Code: Select all

/ ProjektilMotionState.h - My custom MotionState
#ifndef _PROJEKTIL_MOTION_STATE_H_
#define _PROJEKTIL_MOTION_STATE_H_
 
class ProjektilMotionState : public btMotionState {
protected:
        ork_object *mObj;
        //Ogre::SceneNode *mNode;
 
public:
        btTransform mPos;
 
        ProjektilMotionState (const btTransform &initpos, ork_object *obj);
        virtual ~ProjektilMotionState ();
        void setObject (ork_object *newobj);
        //void setPosition (float x, float y, float z);
        virtual void getWorldTransform (btTransform &worldTrans) const;
        virtual void setWorldTransform (const btTransform &worldTrans);
 
};
 
#endif // _PROJEKTIL_MOTION_STATE_H_
 
// ProjektilMotionState.cpp
#include <kaym_common.h>
 
ProjektilMotionState::ProjektilMotionState (const btTransform &initpos, ork_object *obj) {
        mPos = initpos;
        mObj = obj;
 
        DBG ("Neue ProjektilMotionState Instanz");
}
 
ProjektilMotionState::~ProjektilMotionState () {
 
}
 
void ProjektilMotionState::setObject (ork_object *newobj) {
        mObj = newobj;
}
 
void ProjektilMotionState::getWorldTransform (btTransform &worldTrans) const {
        DBG ("ProjektilMotionState::getWorldTransform");
 
        worldTrans = mPos;
}
 
void ProjektilMotionState::setWorldTransform (const btTransform &worldTrans) {
        if (!mObj || !mObj->node)
                return;
 
        DBG ("ProjektilMotionState::setWorldTransform");
 
        btQuaternion rot = worldTrans.getRotation ();
        mObj->node->setOrientation(rot.w(), rot.x(), rot.y(), rot.z());
        //object_rotate (mObj, rot.w (), rot.x (), rot.z (), rot.y ());
 
        btVector3 pos = worldTrans.getOrigin ();
        mObj->node->setPosition(pos.x(), pos.y(), pos.z());
        //object_move (mObj, pos.x (), pos.z (), pos.y ());
}
 
// projektil.cpp - (De-)Inits Bullet and calls stepSimulation
#include <kaym_common.h>
 
/* Richtet Bullet ein
 * Parameter: Ork Handle
 * Rückgaben: Keine
 */
void projektil_setup (ork_t *ork) { // <- called on start up
        ork->broadphase = new btDbvtBroadphase();
        ork->collisionConfiguration = new btDefaultCollisionConfiguration();
        ork->dispatcher = new btCollisionDispatcher(ork->collisionConfiguration);
        ork->solver = new btSequentialImpulseConstraintSolver;
        ork->dynamicsWorld = new btDiscreteDynamicsWorld(ork->dispatcher, ork->broadphase, ork->solver, ork->collisionConfiguration);
        ork->dynamicsWorld->setGravity(btVector3(0,-10,0));
}
 
/* Gibt Daten von Bullet im Ork Handle wieder frei
 * Parameter: Ork Handle
 * Rückgaben: Keine
 */
void projektil_shutdown (ork_t *ork) {
        delete ork->broadphase;
        delete ork->collisionConfiguration;;
        delete ork->dispatcher;
        delete ork->solver;
        delete ork->dynamicsWorld;
}
 
/* Berechnet den nächsten Physik Schritt und setzt die Objekte entsprechend
 * Parameter: Ork Handle, FrameEvent (von OGRE)
 * Rückgaben: Keine
 */
void projektil_update_handler (int eventid, ork_t *ork, const Ogre::FrameEvent *evt, void *user_data) {
        float hz = ((float)evt->timeSinceLastFrame) ? 1.0f / (float)evt->timeSinceLastFrame : 1.0f;
 
        //DBG ("projektil_update_handler, %fHz", hz);
        ork->dynamicsWorld->stepSimulation (1.0f/hz);
/* Other things I tried: (No change)
	//DBG ("projektil_update_handler, %fHz", hz);
	//ork->dynamicsWorld->stepSimulation ((btScalar)evt->timeSinceLastFrame, 10); //(hz);
	//ork->dynamicsWorld->stepSimulation (0.01f, 20);
	ork->dynamicsWorld->stepSimulation (1/60.f, 10);
*/


}
 
// I use this function to add a rigidBody (Planes or Boxes)
void primitive_setup_physics (ork_primitive *ret, btVector3 pos, btQuaternion rot, btVector3 size, btScalar mass, btVector3 inertia) {
        INFO("Richte Physik ein für ein OrkPrimitive. type = %i Pos(%f %f %f) Size(%f %f %f) Inertia(%f %f %f) State: %p",
                ret->type, pos.getX(), pos.getY(), pos.getZ(), size.getX(), size.getY(), size.getZ(),
                inertia.getX(), inertia.getY(), inertia.getZ(), ret->state);
 
        if (ret->state) {
                ret->world->ork->dynamicsWorld->removeRigidBody (ret->rigidBody);
 
                ret->state->~ProjektilMotionState ();
                delete ret->state;
 
                ret->rigidBody->~btRigidBody ();
                delete ret->rigidBody;
        }
 
        //printf ("Erstelle Physikform... ");
        switch (ret->type) {
                case TYPE_BOX:
                //      printf ("TYPE_BOX ");
                        ret->shape = new btBoxShape (size);
                        break;
                case TYPE_PLANE:
                //      printf ("TYPE_PLANE ");
                        ret->shape = new btStaticPlaneShape (size, 1); // Wofür ist die 1 ?
                        break;
                default:
                        FAIL("Unbekannter OrkPrimitive Typ: %i", ret->type);
                        break;
        }
        //printf ("OK\n");
 
        ret->mass = mass;
        ret->inertia.x = (float)inertia.getX();
        ret->inertia.y = (float)inertia.getY();
        ret->inertia.z = (float)inertia.getZ();

        ret->state = new ProjektilMotionState (btTransform(rot, pos), (ork_object*)ret);
        ret->shape->calculateLocalInertia (mass, inertia);
        btRigidBody::btRigidBodyConstructionInfo BodyCI (mass, ret->state, ret->shape, inertia);
        ret->rigidBody = new btRigidBody (BodyCI);
 
        ret->world->ork->dynamicsWorld->addRigidBody (ret->rigidBody);
        //printf ("OK\n");
}
Some info about my code:
1. In my code the Z-axis is the one pointing up ("Internal" functions are using the "Y-Axis is upwards" scheme though)
2. ork_t is a structure that holds all the data used by the engines. ork_object is a structure that
holds data about a single object.
3. I don't like C++, so I'm using C function names (Have to add extern "C"), so I can code a game in plain C.
4. The obvious one: I hope i didn't forgot any important code part. When you need more info about something, please ask
rather than ignoring my post ...

Here are the ork_t and ork_object Structures:

Code: Select all

#define ORK_OBJECT_HEADER const ork_object_header *header; \
			  ork_world *world; \
			  bool linked; \
			  Ogre::SceneNode *node; \
			  Ogre::MeshPtr mesh; \
			  Ogre::Entity *entity; \
			  btCollisionShape *shape; \
			  btDefaultMotionState *state; \
			  btRigidBody *rigidBody;
/* The ork_object struct is reimplemented by any displayable object
 * Its used so that one can use the "standard functions" (like object_move, _rotate, ...)
 * on any graphical object. The only thing any of these structures shares
 * is the ORK_OBJECT_HEADER
 */
typedef struct struct_ork_object {
	ORK_OBJECT_HEADER
} ork_object;

// The OrkPrimitive struct is one of these graphical objects
typedef struct {
	ORK_OBJECT_HEADER

	int type;
	vec3 pos;
	vec3 rot;
	vec3 scale;
	vec3 inertia;
	btScalar mass;
	bool visible;
} ork_primitive;

typedef struct struct_ork_t {
	/// Ork.World
	ork_world *world;

	/// OGRE
	Root *mRoot;
	RenderWindow *mWindow;
	OrkFrameListener *mFrameListener;

	/// Bullet
	btBroadphaseInterface *broadphase;
	btDefaultCollisionConfiguration *collisionConfiguration;
	btCollisionDispatcher *dispatcher;
	btSequentialImpulseConstraintSolver *solver;
	btDiscreteDynamicsWorld *dynamicsWorld;

	/// Python
	pyork_t *py;

	/// LibLen
	len_handle_t *events;

} ork_t;

// My 3D vector
typedef struct {
	float x;
	float y;
	float z;
} vec3;

So, i hope that was enough (too much...?) input for understanding my code so far ;)
Thanks in advance :)
jrk
Posts: 17
Joined: Tue Aug 18, 2009 2:48 pm

Re: Newbie: stepSimulation does nothing

Post by jrk »

I don't see what is going wrong, but I have made a successful ogre/bullet hello world (ogre head falls to the ground)
The code I've attached is derived from a class called BaseApplication which is derived from:
public Ogre::FrameListener, public Ogre::WindowEventListener, public OIS::KeyListener, public OIS::MouseListener, OgreBites::SdkTrayListener

That architecture comes from running the appwizard found here:
http://code.google.com/p/ogreappwizards/

Hopefully that is enough background, here is the code:

header:

Code: Select all

/*
-----------------------------------------------------------------------------
Filename:    OgreBulletHelloWorldApp.h
-----------------------------------------------------------------------------


This source file is generated by the
   ___                   _              __    __ _                  _ 
  /___\__ _ _ __ ___    /_\  _ __  _ __/ / /\ \ (_)______ _ _ __ __| |
 //  // _` | '__/ _ \  //_\\| '_ \| '_ \ \/  \/ / |_  / _` | '__/ _` |
/ \_// (_| | | |  __/ /  _  \ |_) | |_) \  /\  /| |/ / (_| | | | (_| |
\___/ \__, |_|  \___| \_/ \_/ .__/| .__/ \/  \/ |_/___\__,_|_|  \__,_|
      |___/                 |_|   |_|                                 
      Ogre 1.7.x Application Wizard for VC10 (August 2010)
      http://code.google.com/p/ogreappwizards/
-----------------------------------------------------------------------------
*/
#ifndef __OgreBulletHelloWorldApp_h_
#define __OgreBulletHelloWorldApp_h_
#include "btBulletDynamicsCommon.h"
#include "BaseApplication.h"
#if OGRE_PLATFORM == OGRE_PLATFORM_WIN32
#include "../res/resource.h"
#endif


class OgreBulletHelloWorldApp : public BaseApplication
{
public:
    OgreBulletHelloWorldApp(void);
    virtual ~OgreBulletHelloWorldApp(void);

protected:
    virtual void createScene(void);
	// Ogre::FrameListener
    virtual bool frameRenderingQueued(const Ogre::FrameEvent& evt);

private:
	btDiscreteDynamicsWorld* dynamicsWorld;
	btSequentialImpulseConstraintSolver* solver;
	btBroadphaseInterface* overlappingPairCache;
	btCollisionDispatcher* dispatcher;
	btDefaultCollisionConfiguration* collisionConfiguration;
	btAlignedObjectArray<btCollisionShape*> collisionShapes;
};

#endif // #ifndef __OgreBulletHelloWorldApp_h_

.cpp

Code: Select all

/*
-----------------------------------------------------------------------------
Filename:    OgreBulletHelloWorldApp.cpp
-----------------------------------------------------------------------------


This source file is generated by the
   ___                   _              __    __ _                  _ 
  /___\__ _ _ __ ___    /_\  _ __  _ __/ / /\ \ (_)______ _ _ __ __| |
 //  // _` | '__/ _ \  //_\\| '_ \| '_ \ \/  \/ / |_  / _` | '__/ _` |
/ \_// (_| | | |  __/ /  _  \ |_) | |_) \  /\  /| |/ / (_| | | | (_| |
\___/ \__, |_|  \___| \_/ \_/ .__/| .__/ \/  \/ |_/___\__,_|_|  \__,_|
      |___/                 |_|   |_|                                 
      Ogre 1.7.x Application Wizard for VC10 (August 2010)
      http://code.google.com/p/ogreappwizards/
-----------------------------------------------------------------------------
*/

#include "OgreBulletHelloWorldApp.h"

//-------------------------------------------------------------------------------------
OgreBulletHelloWorldApp::OgreBulletHelloWorldApp(void)
{
}
//-------------------------------------------------------------------------------------
OgreBulletHelloWorldApp::~OgreBulletHelloWorldApp(void)
{
	int i;
		//remove the rigidbodies from the dynamics world and delete them
	for (i=dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
	{
		btCollisionObject* obj = dynamicsWorld->getCollisionObjectArray()[i];
		btRigidBody* body = btRigidBody::upcast(obj);
		if (body && body->getMotionState())
		{
			delete body->getMotionState();
		}
		dynamicsWorld->removeCollisionObject( obj );
		delete obj;
	}

	//delete collision shapes
	for (int j=0;j<collisionShapes.size();j++)
	{
		btCollisionShape* shape = collisionShapes[j];
		collisionShapes[j] = 0;
		delete shape;
	}

	//delete dynamics world
	delete dynamicsWorld;

	//delete solver
	delete solver;

	//delete broadphase
	delete overlappingPairCache;

	//delete dispatcher
	delete dispatcher;

	delete collisionConfiguration;
}

//-------------------------------------------------------------------------------------
void OgreBulletHelloWorldApp::createScene(void)
{
    Ogre::Entity* ogreHead = mSceneMgr->createEntity("Head", "ogrehead.mesh");

    Ogre::SceneNode* headNode = mSceneMgr->getRootSceneNode()->createChildSceneNode();
    headNode->attachObject(ogreHead);

    // Set ambient light
    mSceneMgr->setAmbientLight(Ogre::ColourValue(0.5, 0.5, 0.5));

    // Create a light
    Ogre::Light* l = mSceneMgr->createLight("MainLight");
    l->setPosition(20,80,50);

	/////////////////////////////////////////////////////////////////////////

	/////////////////////////////////////////////////////////////////////////
	///collision configuration contains default setup for memory, collision setup. Advanced users can create their own configuration.
	collisionConfiguration = new btDefaultCollisionConfiguration();
	///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
	dispatcher = new	btCollisionDispatcher(collisionConfiguration);
	///btDbvtBroadphase is a good general purpose broadphase. You can also try out btAxis3Sweep.
	overlappingPairCache = new btDbvtBroadphase();
		///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
	solver = new btSequentialImpulseConstraintSolver;

	dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,overlappingPairCache,solver,collisionConfiguration);

	dynamicsWorld->setGravity(btVector3(0,-10,0));

	///create a few basic rigid bodies
	btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));

		//keep track of the shapes, we release memory at exit.
	//make sure to re-use collision shapes among rigid bodies whenever possible!
	//btAlignedObjectArray<btCollisionShape*> collisionShapes;

	collisionShapes.push_back(groundShape);

	btTransform groundTransform;
	groundTransform.setIdentity();
	groundTransform.setOrigin(btVector3(0,-56,0));

	{
		btScalar mass(0.);

		//rigidbody is dynamic if and only if mass is non zero, otherwise static
		bool isDynamic = (mass != 0.f);

		btVector3 localInertia(0,0,0);
		if (isDynamic)
			groundShape->calculateLocalInertia(mass,localInertia);

		//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
		btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
		btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,groundShape,localInertia);
		btRigidBody* body = new btRigidBody(rbInfo);

		//add the body to the dynamics world
		dynamicsWorld->addRigidBody(body);
	}


	{
		//create a dynamic rigidbody

		//btCollisionShape* colShape = new btBoxShape(btVector3(1,1,1));
		btCollisionShape* colShape = new btSphereShape(btScalar(1.));
		collisionShapes.push_back(colShape);

		/// Create Dynamic Objects
		btTransform startTransform;
		startTransform.setIdentity();
		startTransform.setOrigin(btVector3(0,0,0));

		btScalar	mass(1.f);

		//rigidbody is dynamic if and only if mass is non zero, otherwise static
		bool isDynamic = (mass != 0.f);

		btVector3 localInertia(0,0,0);
		if (isDynamic)
			colShape->calculateLocalInertia(mass,localInertia);

			startTransform.setOrigin(btVector3(2,10,0));
		
			//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
			btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
			btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
			btRigidBody* body = new btRigidBody(rbInfo);
			body->setUserPointer(headNode);
			dynamicsWorld->addRigidBody(body);
	}


	/////////////////////////////////////////////////////////////////////////
}




bool OgreBulletHelloWorldApp::frameRenderingQueued(const Ogre::FrameEvent& evt)
{
    if(mWindow->isClosed())
        return false;

    if(mShutDown)
        return false;

    //Need to capture/update each device
    mKeyboard->capture();
    mMouse->capture();

    mTrayMgr->frameRenderingQueued(evt);

    if (!mTrayMgr->isDialogVisible())
    {
        mCameraMan->frameRenderingQueued(evt);   // if dialog isn't up, then update the camera
        if (mDetailsPanel->isVisible())   // if details panel is visible, then update its contents
        {
            mDetailsPanel->setParamValue(0, Ogre::StringConverter::toString(mCamera->getDerivedPosition().x));
            mDetailsPanel->setParamValue(1, Ogre::StringConverter::toString(mCamera->getDerivedPosition().y));
            mDetailsPanel->setParamValue(2, Ogre::StringConverter::toString(mCamera->getDerivedPosition().z));
            mDetailsPanel->setParamValue(4, Ogre::StringConverter::toString(mCamera->getDerivedOrientation().w));
            mDetailsPanel->setParamValue(5, Ogre::StringConverter::toString(mCamera->getDerivedOrientation().x));
            mDetailsPanel->setParamValue(6, Ogre::StringConverter::toString(mCamera->getDerivedOrientation().y));
            mDetailsPanel->setParamValue(7, Ogre::StringConverter::toString(mCamera->getDerivedOrientation().z));
        }
    }

	double dt = evt.timeSinceLastFrame;
	///////////////////////BULLET STUFF/////////////////////////
		//dynamicsWorld->stepSimulation(1.f/60.f,10);
		dynamicsWorld->stepSimulation(dt,10);
		
		//print positions of all objects
		for (int j=dynamicsWorld->getNumCollisionObjects()-1; j>=0 ;j--)
		{
			btCollisionObject* obj = dynamicsWorld->getCollisionObjectArray()[j];
			btRigidBody* body = btRigidBody::upcast(obj);
			if (body && body->getMotionState())
			{
				btTransform trans;
				body->getMotionState()->getWorldTransform(trans);
				printf("world pos = %f,%f,%f\n",float(trans.getOrigin().getX()),float(trans.getOrigin().getY()),float(trans.getOrigin().getZ()));

				Ogre::SceneNode* node = static_cast<Ogre::SceneNode *> (body->getUserPointer());
				if (node)
				{
					Ogre::Vector3 pos(float(trans.getOrigin().getX()),float(trans.getOrigin().getY()),float(trans.getOrigin().getZ()));
					node->setPosition(pos);
				}
			}
		}
	///////////////////////BULLET STUFF/////////////////////////



    return true;
}





#if OGRE_PLATFORM == OGRE_PLATFORM_WIN32
#define WIN32_LEAN_AND_MEAN
#include "windows.h"
#endif

#ifdef __cplusplus
extern "C" {
#endif

#if OGRE_PLATFORM == OGRE_PLATFORM_WIN32
    INT WINAPI WinMain( HINSTANCE hInst, HINSTANCE, LPSTR strCmdLine, INT )
#else
    int main(int argc, char *argv[])
#endif
    {
        // Create application object
        OgreBulletHelloWorldApp app;

        try {
            app.go();
        } catch( Ogre::Exception& e ) {
#if OGRE_PLATFORM == OGRE_PLATFORM_WIN32
            MessageBox( NULL, e.getFullDescription().c_str(), "An exception has occured!", MB_OK | MB_ICONERROR | MB_TASKMODAL);
#else
            std::cerr << "An exception has occured: " <<
                e.getFullDescription().c_str() << std::endl;
#endif
        }

        return 0;
    }

#ifdef __cplusplus
}
#endif

Post Reply