PSP Performance

SteveDH
Posts: 4
Joined: Thu Apr 29, 2010 2:12 pm

PSP Performance

Post by SteveDH »

Just wondering if this is what I should expect on the PSP (222Mhz) or if possibly I'm doing something wrong.

I am trying to do a bowling game.
the pins are represented using a compound object made up if a cylinder and a sphere, about the minimum I can get away with.

The ground is a btBvhTriangleMeshShape using a btTriangleIndexVertexArray and is only margionally slower than if its replaced with a box.

A bowling ball can be thrown at 20mps
the psp is running at 30fps
so I'm chopping that by 8 or 1/240th sec meaning that the ball can travel just over 8 cms in a timestep.

usually the game grinds to a halt as soon as the ball hits the pins and they wake up, but for testing purposes I'm just keeping the pins awake and these times are just for them standing on the ground.

ideally I need to execute those 8 steps in less than a 30th of a second, or 33ms

at present those 8 steps take 120ms so I'm stuffed.
collision seems to be the biggest problem, but maybe I'm just doing something wrong

below is a BT profile dump as well as output from a PC profile.. can anyone spot anything wrong?

thanks
Steve

*****************************************************************************************


----------------------------------
Profiling: Root (total running time: 126.720 ms) ---
0 -- stepSimulation (99.50 ) :: 126.080 ms / frame (1 calls)
Unaccounted: (0.505 ) :: 0.640 ms
...----------------------------------
...Profiling: stepSimulation (total running time: 126.080 ms) ---
...0 -- synchronizeMotionStates (0.81 ) :: 1.024 ms / frame (8 calls)
...1 -- internalSingleStepSimulation (98.68 ) :: 124.416 ms / frame (8 calls)
...Unaccounted: (0.508 ) :: 0.640 ms
......----------------------------------
......Profiling: internalSingleStepSimulation (total running time: 124.416 ms) ---
......0 -- updateActivationState (0.31 ) :: 0.384 ms / frame (8 calls)
......1 -- updateActions (0.10 ) :: 0.128 ms / frame (8 calls)
......2 -- integrateTransforms (1.24 ) :: 1.536 ms / frame (8 calls)
......3 -- solveConstraints (30.45 ) :: 37.888 ms / frame (8 calls)
......4 -- calculateSimulationIslands (0.51 ) :: 0.640 ms / frame (8 calls)
......5 -- performDiscreteCollisionDetection (64.40 ) :: 80.128 ms / frame (8 calls)
......6 -- predictUnconstraintMotion (1.34 ) :: 1.664 ms / frame (8 calls)
......Unaccounted: (1.646 ) :: 2.048 ms
.........----------------------------------
.........Profiling: solveConstraints (total running time: 37.888 ms) ---
.........0 -- solveGroup (85.81 ) :: 32.512 ms / frame (8 calls)
.........1 -- processIslands (8.45 ) :: 3.200 ms / frame (8 calls)
.........2 -- islandUnionFindAndQuickSort (2.03 ) :: 0.768 ms / frame (8 calls)
.........Unaccounted: (3.716 ) :: 1.408 ms
............----------------------------------
............Profiling: solveGroup (total running time: 32.512 ms) ---
............0 -- solveGroupCacheFriendlyIterations (66.93 ) :: 21.760 ms / frame (8 calls)
............1 -- solveGroupCacheFriendlySetup (28.74 ) :: 9.344 ms / frame (8 calls)
............Unaccounted: (4.331 ) :: 1.408 ms
.........----------------------------------
.........Profiling: performDiscreteCollisionDetection (total running time: 80.128 ms) ---
.........0 -- dispatchAllCollisionPairs (95.85 ) :: 76.800 ms / frame (8 calls)
.........1 -- calculateOverlappingPairs (0.80 ) :: 0.640 ms / frame (8 calls)
.........2 -- updateAabbs (1.60 ) :: 1.280 ms / frame (8 calls)
.........Unaccounted: (1.757 ) :: 1.408 ms


*****************************************************************************************
PC Profile.. for entire game frame, not just physics

9% [536] <kernel>
6% [338] btGjkPairDetector::getClosestPointsNonVirtual(const btDiscreteCollisionDetectorInterface::ClosestPointInput &, btDiscreteCollisionDetectorInterface::Result &, btIDebugDraw *)
5% [279] btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGeneric(btRigidBody &, btRigidBody &, const btSolverConstraint &)
5% [276] btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimit(btRigidBody &, btRigidBody &, const btSolverConstraint &)
4% [255] btVoronoiSimplexSolver::updateClosestVectorAndPoints(void)
3% [181] btTriangleMeshShape::getAabb(const btTransform &, btVector3 &, btVector3 &) const
3% [180] btCompoundCollisionAlgorithm::processCollision(btCollisionObject *, btCollisionObject *, const btDispatcherInfo &, btManifoldResult *)
3% [174] btSequentialImpulseConstraintSolver::setupContactConstraint(btSolverConstraint &, btCollisionObject *, btCollisionObject *, btManifoldPoint &, const btContactSolverInfo &, btVector3 &, float &, float &, btVector3 &, btVector3 &)
3% [169] btCompoundLeafCallback::Process(const btDbvtNode *)
3% [149] btQuantizedBvh::walkStacklessQuantizedTree(btNodeOverlapCallback *, unsigned short *, unsigned short *, int, int) const
3% [148] btPersistentManifold::refreshContactPoints(const btTransform &, const btTransform &)
2% [123] btVoronoiSimplexSolver::closestPtPointTriangle(const btVector3 &, const btVector3 &, const btVector3 &, const btVector3 &, btSubSimplexClosestResult &)
2% [118] TryMalloc(int)
2% [109] btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold *, const btContactSolverInfo &)
2% [108] btConvexShape::localGetSupportVertexWithoutMarginNonVirtual(const btVector3 &) const
2% [104] Free(void *)
2% [101] btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstraint &, const btVector3 &, btRigidBody *, btRigidBody *, btManifoldPoint &, const btVector3 &, const btVector3 &, btCollisionObject *, btCollisionObject *, float, float, float)
2% [99] btSequentialImpulseConstraintSolver::solveSingleIteration(int, btCollisionObject **, int, btPersistentManifold **, int, btTypedConstraint **, int, const btContactSolverInfo &, btIDebugDraw *, btStackAlloc *)
2% [95] btCompoundShape::getAabb(const btTransform &, btVector3 &, btVector3 &) const
1% [76] btQuantizedBvh::reportAabbOverlappingNodex(btNodeOverlapCallback *, const btVector3 &, const btVector3 &) const
1% [74] btConvexConvexAlgorithm::processCollision(btCollisionObject *, btCollisionObject *, const btDispatcherInfo &, btManifoldResult *)
1% [70] btConvexTriangleCallback::processTriangle(btVector3 *, int, int)
1% [52] sceSasCore
1% [51] btManifoldResult::addContactPoint(const btVector3 &, const btVector3 &, float)
1% [49] btTransform::inverse(void) const
1% [45] operator*(const btMatrix3x3 &, const btMatrix3x3 &){4}
1% [44] __0f20t00HMyNodeOverlapCallback__LA____0fWbtBvhTriangleMeshShapeTprocessAllTrianglesP6SbtTriangleCallbackRC6JbtVector3TCKLprocessNodeiTB
1% [38] btCylinderShape::getAabb(const btTransform &, btVector3 &, btVector3 &) const
1% [32] btConvexTriangleCallback::setTimeStepAndCounters(float, const btDispatcherInfo &, btManifoldResult *)
1% [31] btVoronoiSimplexSolver::closestPtPointTetrahedron(const btVector3 &, const btVector3 &, const btVector3 &, const btVector3 &, const btVector3 &, btSubSimplexClosestResult &)
1% [29] btVoronoiSimplexSolver::pointOutsideOfPlane(const btVector3 &, const btVector3 &, const btVector3 &, const btVector3 &, const btVector3 &)
1% [29] btVoronoiSimplexSolver::inSimplex(const btVector3 &)
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: PSP Performance

Post by Erwin Coumans »

8 Iterations is quite a lot, it would help most if you can make it work using fewer iterations, using continuous collision detection only for the ball (this might require some work but it is possible).

A few other things you could try:

Code: Select all

	///the following 3 lines increase the performance dramatically, with a little bit of loss of quality
	//don't recalculate friction values each frame
	m_dynamicsWorld->getSolverInfo().m_solverMode |=SOLVER_ENABLE_FRICTION_DIRECTION_CACHING; 
	 //few solver iterations 
	dynamicsWorld->getSolverInfo().m_numIterations = 4;
	//fewer active contact points: discard them once the distance becomes positive
	m_defaultContactProcessingThreshold = 0.f;//used when creating bodies: body->setContactProcessingThreshold(...);
Futhermore you might want to optimized/implement the top functions in SIMD (btGjkPairDetector::getClosestPointsNonVirtual, btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGeneric).

Thanks,
Erwin