Strange behavior of contact (force-dependent slip)

Post Reply
NorbertBraun
Posts: 4
Joined: Sat Jun 06, 2015 10:58 pm

Strange behavior of contact (force-dependent slip)

Post by NorbertBraun »

Hi,

I have the following situation: a cube (btBoxShape) is sitting on a plane (btStaticPlaneShape). Gravity is disabled. A force is applied to the cube in the contact plane. In my understanding, this force should not cause the cube to move as long as the tangential component is smaller than mu times the normal component of the force. I have mu=1.

What I observe is that the cube picks up, essentially instantly, a small velocity tangential to the plane. The velocity is proportional to the tangential component of the force, independent of the normal component, independent of the cubes mass and roughly inversely proportional to the cubes moment of inertia. It is also proportional to the simulation time step, adding to my suspicion that it is some unphysical simulation artifact. The code I use to debug this is included below.

Does anyone know why this is happening and how I could get rid of it? I am trying to simulate a physical system, so changing the cubes mass or moment of inertia is not really an option. Making the time step smaller does work, but requires (for the actual simulation) a time step of around 0.1ms (1e-4 s) to work, so things become really slow.

Thanks for any answers,

Norbert

Code: Select all

#include <iostream>
#include <btBulletDynamicsCommon.h>

int main()
{
    btBroadphaseInterface* broadphase = new btDbvtBroadphase();
    
    btDefaultCollisionConfiguration* collisionConf = new btDefaultCollisionConfiguration();
    btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collisionConf);
    
    btSequentialImpulseConstraintSolver* solver = new btSequentialImpulseConstraintSolver();
    
    btDiscreteDynamicsWorld* world = new btDiscreteDynamicsWorld(dispatcher, broadphase, solver, collisionConf);
    world->setGravity(btVector3(0., 0., 0.));
    
    btStaticPlaneShape* floorS = new btStaticPlaneShape(btVector3(0., 0., 1.), 0.);
    btRigidBody::btRigidBodyConstructionInfo floorInfo(0., new btDefaultMotionState(btTransform(btQuaternion(0., 0., 0., 1.), btVector3(0., 0., -.5))), floorS, btVector3(0., 0., 0.));
    btRigidBody* floorB = new btRigidBody(floorInfo);
    floorB->setFriction(1.);
    world->addRigidBody(floorB);
    
    btBoxShape* bodyS = new btBoxShape(btVector3(.5, .5, .5));
    
    btRigidBody::btRigidBodyConstructionInfo info(1., new btDefaultMotionState(btTransform(btQuaternion(0., 0., 0., 1.), btVector3(0., 0., 0.))), bodyS, btVector3(1., 1., 1.));
    info.m_linearDamping = btScalar(0.);
    info.m_angularDamping = btScalar(0.);
    info.m_linearSleepingThreshold = btScalar(0.);
    info.m_angularSleepingThreshold = btScalar(0.);
    info.m_additionalDamping = false;
    btRigidBody* body = new btRigidBody(info);
    body->setFriction(1.);
    world->addRigidBody(body);
    
    const double dt = 1e-3;
    for(unsigned int t_step = 0; t_step < 10000; t_step++) {
        const double t = t_step * dt;
        
        btVector3 pos = body->getCenterOfMassPosition();
        btVector3 vel = body->getLinearVelocity();
        
        std::cout << t << " ";
        std::cout << pos.x() << " " << pos.y() << " " << pos.z() << " ";
        std::cout << vel.x() << " " << vel.y() << " " << vel.z() << " ";
        std::cout << std::endl;
        
        body->applyForce(btVector3(500., 0., -1000.), btVector3(0., 0., -.5));
        
        world->stepSimulation(dt, 1, dt);
    }
    
    world->removeRigidBody(body);
    delete body->getMotionState();
    delete body;
    delete bodyS;
    
    delete world;
    delete solver;
    delete dispatcher;
    delete collisionConf;
    delete broadphase;
    
    return 0;
}
Basroil
Posts: 463
Joined: Fri Nov 30, 2012 4:50 am

Re: Strange behavior of contact (force-dependent slip)

Post by Basroil »

That simple scene should be capable of running tens of thousands of frames per second on any i series intel chip or FX series AMD desktop chip. The reason it's slow is likely your cout commands. I have a simulation running with Dantzig solver at 240fps with 36 hinge constrants (overconstrained too) and a few collision points and it doesn't even hit 30% of one core on my 3.4GHz i5 (even with all my other, much less efficient code forced to run on the same core). Perhaps if you mean to simulate giant islands with hundreds of constraints it might be an issue.

There are a few other things you can try as well though (won't fix sliding down inclines all the time though, since if the issue is contact related higher fps is the easiest solution):
1) Try using higher solver iterations, start with 1000 and search down to an acceptable combination of performance and accuracy
2) Try enabling randomized constraints orders. Might help in some cases.
3) Experiment with a different collision shape, perhaps a convex hull over the box shape (visually identical, method of contact calculation changes)
4) Try increasing damping by a tiny amount
NorbertBraun
Posts: 4
Joined: Sat Jun 06, 2015 10:58 pm

Re: Strange behavior of contact (force-dependent slip)

Post by NorbertBraun »

Hello,

thanks for your suggestions. Unfortunately, none of them seem to work for me...
  • My laptop (Core2 Duo P9700 @2.80GHz) takes 1.48s for 10000 steps (no cout) and 1.59s (with cout), so cout seems to be less of an issue than my old computer (note that Bullet is compiled with double precision). In any case, the comment about the speed applied to the actual simulation (a humanoid robot whose feet are modeled as boxes), which runs at about 1000 fps on my computer.
  • Using btDantzigSolver instead of btSequentialImpulseConstraintSolver makes no difference.
  • Setting numIterations to 1000 makes btSequentialImpulseConstraintSolver run much slower (Dantzig is less affected) but does not otherwise change the result. SOLVER_RANDMIZE_ORDER does not make a difference either.
  • Adding damping does not seem to make a difference. Enabling sleeping causes the box to "fall asleep" and stop after 2s, but that's not really helpful for me.
  • Using btConvexHullShape (with margin=0) instead of btBoxShape makes no difference. With the default margin, the box "drops" onto the plane, but behaves the same afterwards.
One thing that does change with the various options (in particular btSequentialImpulseConstraintSolver vs. btDantzigSolver) is the "spikiness" of the tangential velocity. However, the average velocity (and hence the position over time) is unaffected.

Best regards,

Norbert
NorbertBraun
Posts: 4
Joined: Sat Jun 06, 2015 10:58 pm

Re: Strange behavior of contact (force-dependent slip)

Post by NorbertBraun »

Hello again,

re-phrasing the problem as "object sliding down inclines", as your post suggests, and googling yields a fairly plausible explanation for the observed behavior: http://gamedev.stackexchange.com/questi ... e-gradient. In short, the box penetrates the plane in the direction of the force, then gets pushed out again in the direction of the plane normal, which yields a net motion tangential to the plane. This would also explain why I do not observe the effect in ODE, as ODE (I think) lets the objects come to rest with slight penetration.

Does this make sense? Does anybody know how I might get ODE-like behavior in Bullet?

Best regards,

Norbert
Basroil
Posts: 463
Joined: Fri Nov 30, 2012 4:50 am

Re: Strange behavior of contact (force-dependent slip)

Post by Basroil »

NorbertBraun wrote: Does this make sense? Does anybody know how I might get ODE-like behavior in Bullet?
You can try tweaking the erp and cmf numbers (look at the ODE manual for a good explanation as to what they do), it's also often necessary when using higher framerate simulations to avoid issues with large forces causing instability.
NorbertBraun
Posts: 4
Joined: Sat Jun 06, 2015 10:58 pm

Re: Strange behavior of contact (force-dependent slip)

Post by NorbertBraun »

It turns out that older versions of bullet behave differently, and the problem is much less severe there. The git revision that appears to have introduced the current behavior is 7f29aeb ("fix broken force feedback in constraint solver, thanks to John Hsu for the report"). As far as I can tell, the change responsible is the replacement of solverBody*.m_*Velocity by body*->get*Velocity() in btSequentialImpulseConstraintSolver.cpp, but I presently do not really understand the code.

I should also note that my problem is related to applying a torque on the box while pushing it down, a fact somewhat obscured by the use of body->applyForce() in the original example. However, if I apply the tangential force at the boxes center of mass, the problem disappears completely, while applying a torque, i.e.

Code: Select all

body->applyForce(btVector3(0., 0., -10000.), btVector3(0., 0., 0.));
body->applyTorque(btVector3(100., 0., 0.));
causes a linear motion of the box tangential to the plane.

The boxes velocity (in the current version of Bullet) is given, to a surprisingly high accuracy, by the equation

v_t = 1/2 * T_x/I_x * dt

where T_x is the x component of the torque, I_x is the moment of inertia around the x axis and dt is the time step. It turns out that the box can move in both tangetial directions, so v_t is the norm of the tangential velocity.

v_t is somewhat spiky. The suggestions from the posts above influence its spikyness, and choosing too high a timestep makes the motion become completely erratic, but apart from that, it follows the given equation.
Post Reply