Point to point constraint jacobian row count

Please don't post Bullet support questions here, use the above forums instead.
hop
Posts: 10
Joined: Fri Nov 13, 2009 4:36 pm

Point to point constraint jacobian row count

Post by hop »

I'm trying to get clear on how to formulate constraints and by contrasting the Bullet btPoint2PointConstraint and Box2D b2DistanceJoint I think I am seeing two different approaches to the same problem.

btPoint2PointConstraint makes use of three orthogonal (world) axes to construct 3 Jacobian rows:

Code: Select all

btJacobianEntry	m_jac[3]; //3 orthogonal linear constraints

<snip>

	btVector3	normal(0,0,0);

	for (int i=0;i<3;i++)
	{
		normal[i] = 1;
		new (&m_jac[i]) btJacobianEntry(
			m_rbA.getCenterOfMassTransform().getBasis().transpose(),
			m_rbB.getCenterOfMassTransform().getBasis().transpose(),
			m_rbA.getCenterOfMassTransform()*m_pivotInA - m_rbA.getCenterOfMassPosition(),
			m_rbB.getCenterOfMassTransform()*m_pivotInB - m_rbB.getCenterOfMassPosition(),
			normal,
			m_rbA.getInvInertiaDiagLocal(),
			m_rbA.getInvMass(),
			m_rbB.getInvInertiaDiagLocal(),
			m_rbB.getInvMass());
		normal[i] = 0;
	}
whereas Box2D seems to only use one axis: the axis connecting the points on the two bodies:

Code: Select all

void b2DistanceJoint::InitVelocityConstraints(const b2TimeStep& step)
<snip>
b2Body* b1 = m_body1;
b2Body* b2 = m_body2;
m_u = b2->m_sweep.c + r2 - b1->m_sweep.c - r1;
// Handle singularity.
float32 length = m_u.Length();
if (length > b2_linearSlop)
{
	m_u *= 1.0f / length;
}
else
{
	m_u.Set(0.0f, 0.0f);
}

<snip>

// Cdot = dot(u, v + cross(w, r))
b2Vec2 v1 = b1->m_linearVelocity + b2Cross(b1->m_angularVelocity, r1);
b2Vec2 v2 = b2->m_linearVelocity + b2Cross(b2->m_angularVelocity, r2);
float32 Cdot = b2Dot(m_u, v2 - v1);

float32 impulse = -m_mass * (Cdot + m_bias + m_gamma * m_impulse);
Are these two methods equivalent?

Thanks for any help.
ngbinh
Posts: 117
Joined: Fri Aug 12, 2005 3:47 pm
Location: Newyork, USA

Re: Point to point constraint jacobian row count

Post by ngbinh »

hop wrote:I'm trying to get clear on how to formulate constraints and by contrasting the Bullet btPoint2PointConstraint and Box2D b2DistanceJoint I think I am seeing two different approaches to the same problem.

btPoint2PointConstraint makes use of three orthogonal (world) axes to construct 3 Jacobian rows:

Code: Select all

btJacobianEntry	m_jac[3]; //3 orthogonal linear constraints

<snip>

	btVector3	normal(0,0,0);

	for (int i=0;i<3;i++)
	{
		normal[i] = 1;
		new (&m_jac[i]) btJacobianEntry(
			m_rbA.getCenterOfMassTransform().getBasis().transpose(),
			m_rbB.getCenterOfMassTransform().getBasis().transpose(),
			m_rbA.getCenterOfMassTransform()*m_pivotInA - m_rbA.getCenterOfMassPosition(),
			m_rbB.getCenterOfMassTransform()*m_pivotInB - m_rbB.getCenterOfMassPosition(),
			normal,
			m_rbA.getInvInertiaDiagLocal(),
			m_rbA.getInvMass(),
			m_rbB.getInvInertiaDiagLocal(),
			m_rbB.getInvMass());
		normal[i] = 0;
	}
whereas Box2D seems to only use one axis: the axis connecting the points on the two bodies:

Code: Select all

void b2DistanceJoint::InitVelocityConstraints(const b2TimeStep& step)
<snip>
b2Body* b1 = m_body1;
b2Body* b2 = m_body2;
m_u = b2->m_sweep.c + r2 - b1->m_sweep.c - r1;
// Handle singularity.
float32 length = m_u.Length();
if (length > b2_linearSlop)
{
	m_u *= 1.0f / length;
}
else
{
	m_u.Set(0.0f, 0.0f);
}

<snip>

// Cdot = dot(u, v + cross(w, r))
b2Vec2 v1 = b1->m_linearVelocity + b2Cross(b1->m_angularVelocity, r1);
b2Vec2 v2 = b2->m_linearVelocity + b2Cross(b2->m_angularVelocity, r2);
float32 Cdot = b2Dot(m_u, v2 - v1);

float32 impulse = -m_mass * (Cdot + m_bias + m_gamma * m_impulse);
Are these two methods equivalent?

Thanks for any help.
They are the same. Just Box2D constraint is in 2D while Bullet is in 3D.
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: Point to point constraint jacobian row count

Post by Dirk Gregorius »

This has nothing to do with 2D or 3D. A point to point and a distance constraint are two different things.

Distance:
C = |x2 - x1| - L0 = 0

Point2Point:
C = x2 + r2 - x1 - r1

The first constraint is just one equation while the second is actually three equations. If the distance between x2 and x1 in the first constraint goes to zero the Jacobian becomes singular:

J = ( -(x2 -x1) / |x2 - x1| (x2 -x1) / |x2 - x1| ) .

So this constraint becomes undefined if the constraint error goes to zero the Jacobian . Not a very good choice to model a spherical joint (as e.g. suggested in the J. Bender thesis)

These are the usual problems with constraints. Take the orthogonality condition to block relative angular movement as another example. The Jacobian goes to zero if the constraint error goes to its maximum (geometrically if the axes become parallel). As you can imagine this is numerically not very helpful.

Cheers,
-Dirk
ngbinh
Posts: 117
Joined: Fri Aug 12, 2005 3:47 pm
Location: Newyork, USA

Re: Point to point constraint jacobian row count

Post by ngbinh »

Dirk Gregorius wrote:This has nothing to do with 2D or 3D. A point to point and a distance constraint are two different things.

Distance:
C = |x2 - x1| - L0 = 0

Cheers,
-Dirk
Hmm, this constraint is not linear in term of x1,x2 unless you use current values of them. But then it wont be in the Jacobian anymore as it doesnt involve any variables.
fishboy82
Posts: 91
Joined: Wed Jun 10, 2009 4:01 am

Re: Point to point constraint jacobian row count

Post by fishboy82 »

The first constraint is just one equation while the second is actually three equations. If the distance between x2 and x1 in the first constraint goes to zero the Jacobian becomes singular:
J = ( -(x2 -x1) / |x2 - x1| (x2 -x1) / |x2 - x1| ) .
So what should I do when |x2 - x1| euqal zero, for example , I have a dist constraint with |x2-x1| = c,But due to numerical error and linearlization the dist constraint may not exactly meeted, may be at a time|x2-x1| = 0 ,So in this point what should the Jacobian be like .I browse the posted box2D's code it seems simply set mu = 0, So this means it set the constraint force between these 2 points to be zero, So it seems simply just ignore this constraint when dist = 0?
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: Point to point constraint jacobian row count

Post by Dirk Gregorius »

@ngbinh
I don't get your point. Of course the constraint is not linear. Actually constraints are usually non-linear, but of course the Jacobian exist (but might have singularities).

@fishboy
Good question. I would say prevent this from happening by design. E.g. if you want the distance between two points to be zero don't use a distance constraint, but prefer a point2point constraint since this is well defined in this case. I would choose my constraints such that they are well defined if they are satisfied. If for some reason the points become really coincident you could choose an arbitrary Jacobian. Maybe look at the last positions and build the Jacobian from there. Alternatively just move the points randomly.
hop
Posts: 10
Joined: Fri Nov 13, 2009 4:36 pm

Re: Point to point constraint jacobian row count

Post by hop »

Dirk Gregorius wrote:This has nothing to do with 2D or 3D. A point to point and a distance constraint are two different things.

Distance:
C = |x2 - x1| - L0 = 0

Point2Point:
C = x2 + r2 - x1 - r1
I see! Keeping two points on two bodies coincident means that these points are constrained to have the same position and velocity, whereas keeping two points on two bodies a fixed distance apart does only that i.e. their positions and velocities can be quite different.

I realise now that I should probably be comparing btPoint2PointConstraint with b2RevoluteJoint.

Back to deriving Jacobians and J M^-1 J^T ...

Many thanks.
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: Point to point constraint jacobian row count

Post by Dirk Gregorius »

I realise now that I should probably be comparing btPoint2PointConstraint with b2RevoluteJoint.
Yeap, this is correct. In my opinion the terms constraint and joint are used sloppy sometimes. I would say one uses constraints to model joints and contacts. So in 2D a point2point constraint models a revolute joint while in 3D it models a spherical joint. The book by Shabana "Computational Dynamics" is pretty good and derives the constraints and Jacobians of many joints using just three different constraints. If you are interested in this topic it might be worth reading.


HTH,
-Dirk