help needed:rigid body Kinematic Collisions penetrate

mg-qwq
Posts: 2
Joined: Fri Mar 06, 2020 6:58 am

help needed:rigid body Kinematic Collisions penetrate

Post by mg-qwq »

Hello everyone, I need help,Here is my question.
Requirement
Use Transform to control rigid body motion and collide with other non-static rigid bodies, but not change direction.
Test program
Set rigid body to kinematics

Code: Select all

kBox->setCollisionFlags(kBox->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
kBox->setActivationState(DISABLE_DEACTIVATION);
Use btMotionState to make it move

Code: Select all

void RollingFrictionDemo::stepSimulation(float deltaTime)
{
	CommonRigidBodyBase::stepSimulation(deltaTime);
	if (run123)
	{
		btMotionState* state = kBox->getMotionState();
		btTransform s;
		state->getWorldTransform(s);
		s.setOrigin(s.getOrigin() + btVector3(deltaTime, 0, 0));
		state->setWorldTransform(s);
	
	}
}
Actual effect
Kinematic rigid bodies collide with other rigid bodies and penetrate them
Actual effect.gif
Expected effect
I did a similar test using unity3d
Expected effect.gif
Same problem
Some people in the forum raised similar questions and proposed a solution. After testing, I found that the effect is a bit problematic, Rigid bodies will lateral jitter.

Code: Select all

m_dynamicsWorld->getSolverInfo().m_erp2 = 1.0f;
Same problem.gif
problem
1.How do I change the settings to achieve the effect.
2.Is there a related document describing the role of the btContactSolverInfo property
Thank you!
You do not have the required permissions to view the files attached to this post.
User avatar
drleviathan
Posts: 849
Joined: Tue Sep 30, 2014 6:03 pm
Location: San Francisco

Re: help needed:rigid body Kinematic Collisions penetrate

Post by drleviathan »

When you give a kinematic object a non-zero velocity the object will not move accordingly because Bullet will NOT integrate its motion forward. It moves according to the fresh transform you give it (usually done through a MotionState::setWorldTransform() method) every substep. So when it comes to moving the kinematic object around the velocity stored on its body is not important. However its velocity IS used by the collision algorithm to calculate proper response of dynamic bodies. Therefore: to make dynamic bodies respond more correctly to the motion of a kinematic object: set the kinematic object's velocities to agree with the rate at which its transform is changing.
mg-qwq
Posts: 2
Joined: Fri Mar 06, 2020 6:58 am

Re: help needed:rigid body Kinematic Collisions penetrate

Post by mg-qwq »

drleviathan wrote: Sat Mar 07, 2020 4:40 pm When you give a kinematic object a non-zero velocity the object will not move accordingly because Bullet will NOT integrate its motion forward. It moves according to the fresh transform you give it (usually done through a MotionState::setWorldTransform() method) every substep. So when it comes to moving the kinematic object around the velocity stored on its body is not important. However its velocity IS used by the collision algorithm to calculate proper response of dynamic bodies. Therefore: to make dynamic bodies respond more correctly to the motion of a kinematic object: set the kinematic object's velocities to agree with the rate at which its transform is changing.
Hello, Drleviathan, I am using the bullet engine for the first time,set the kinematic object's velocities to agree with the rate at which its transform is changing how to use code to achieve it, I have tried to set the speed for a kinematic object, but it has no effect, Attached is my test code,Thank.
You do not have the required permissions to view the files attached to this post.
User avatar
drleviathan
Posts: 849
Joined: Tue Sep 30, 2014 6:03 pm
Location: San Francisco

Re: help needed:rigid body Kinematic Collisions penetrate

Post by drleviathan »

One way to do it would be to derive your own KinematicMotionState from btMotionState and use that instead.

Of course, you'd have to set the velocities to what you'd like them to be and make sure the kinematic object is active.

Note: I copied and then modified this from working code I copied from Bullet a while ago but I did not compile or test this version so there might be bugs. Use at your own risk and fix as necessary:

Code: Select all

const btScalar DEFAULT_SUBSTEP = 1.0 / 60.0;

class KinematicMotionState : public btMotionSTate {
    btTransform m_transform;
    btRigidBody* m_body;
    btScalar m_fixedSubstep;
public:
    KinematicMotionState(btRigidBody* body, const btTransform& t) :
        m_transform(t),
        m_bodyPointer(body),
        m_fixedSubstep(DEFAULT_SUBSTEP)
    {
        assert(m_body);
        m_body->setWorldTransform(m_transform);
    }

    // Note: we store the velocities in the body itself
    void setLinearVelocity(const btVector3& v) { m_body->setLinearVelocity(v); }
    void setAngularVelocity(const btVector3& w) { m_body->setAngularVelocity(w); }

    void setFixedSubstep(btScalar dt) { m_fixedSubstep = dt; }

    void subStepForward() {
        // Linear part is easy
        btVector3 newPosition = m_transform.getOrigin() + m_body->getLinearVelocity() * m_fixedSubstep;

        // Angular part is trickier if you want to do it like Bullet
        //
        // Bullet uses an exponential map approximation technique to integrate rotation.
        // The reason for this is to make it easy to compute the derivative of angular motion for various consraints.
        // Here we reproduce the same approximation so that our extrapolations agree well with Bullet's integration.
        //
        // Exponential map
        // google for "Practical Parameterization of Rotations Using the Exponential Map", F. Sebastian Grassia

        btVector3 axis = m_body->getLinearVelocity();
        btScalar angle = axis.length() * m_fixedSubstep;
        // limit the angular motion because the exponential approximation fails for large steps
        const btScalar ANGULAR_MOTION_THRESHOLD = 0.5 * PI_OVER_TWO;
        if (angle > ANGULAR_MOTION_THRESHOLD) {
            angle = ANGULAR_MOTION_THRESHOLD;
        }

        const btScalar MIN_ANGLE = 0.001;
        if (angle < MIN_ANGLE) {
            // for small angles use Taylor's expansion of sin(x):
            //   sin(x) = x - (x^3)/(3!) + ...
            // where: x = angle/2
            //   sin(angle/2) = angle/2 - (angle*angle*angle)/48
            // but (angle = speed * dt) and we want to normalize the axis by dividing by speed
            // which gives us:
            axis *= m_fixedSubstep * (0.5 - 0.020833333333 * angle * angle);
        } else {
            axis *= (sinf(0.5 * angle) * m_fixedSubstep / angle);
        }
        btQuaternion deltaRotation(cosf(0.5 * angle), axis.x, axis.y, axis.z);

        // DANGER! btTransform operators do not normalize their result,
        // so we MUST normalize the rotation part in a feedback loop like this
        // else risk wandering into NaN territory
        btQuaternion newRotation = deltaRotation * m_transform.getRotation();
        newRotation.safeNormalize();

        // finally...
        m_transform.setOrigin(newPosition);
        m_transform.setRotation(newRotation);
    }

    ///synchronizes world transform from user to physics
    void getWorldTransform(btTransform & centerOfMassWorldTrans) const override {
        // assume this is called every substep, so integrate here
        subStepForward();
        centerOfMassWorldTrans = m_transform;
    }

    ///synchronizes world transform from physics to user
    ///Bullet only calls the update of worldtransform for active dynamic objects
    void setWorldTransform(const btTransform& centerOfMassWorldTrans) override {
        // do nothing
        // this is a kinematic object
        // user tells physics, not the other way around
    }
};