Initial conditions in joints

A place to discuss everything related to Newton Dynamics.

Moderators: Sascha Willems, walaber

Initial conditions in joints

Postby blackbird_dream » Wed Sep 25, 2024 5:14 am

Hello all.
Back to this forum after a while.
Thanks to Dave and its engine I am working on a model of autonomous biped with ND4.
I'm currently stuck with problems of Initial conditions in joints.
I'd like to know how to add an offset member in JointHinge and JointDoubleHinge so that I can set the biped in a given pose before making him walk.
More precisely, If the offset is set to alpha, the joint is initially set with an angle of alpha and not zero.
Ideally, a herited class should be fine.
thks
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby blackbird_dream » Wed Sep 25, 2024 10:28 am

For the moment my solution is to build a subclass where I can set the target angle to the offset value (for the rest position to be shifted), then shift the upper and lower limits (ading the offset to the limits) and build the joint with the bodies pre-rotated in the desired pose. This needs to compute the absolute offset which is the summation of all parent offsets.
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby Julio Jerez » Sat Sep 28, 2024 8:11 am

That's a difficult thing to do the way you stated it, as you said, physics is an initial condition value problem. A joint cannot be set to an arbitrary state and expect that the integrator will just jump to that state.
When a simulation starts, the joint parameters are expected to be an accurate representation of the relation (velocity and position) between the two bodies it connects. The joint code relies on that value to be accurate and then is add a correction to it.
If the value does not represent the start of the bodied, the correction will cause huge deltas that will lead to explosions.
The offset trick, you are thinking about will not help, believe me I tried, with in the pass unsuccessfully.
The rule of thumb is that in a joint you can change almost anything to steer the state,
but you cannot change the state after the initialization, only the integrator can change the state.
This rule is not only for joints, it is, also for bodies.

The way to do it is by having a complete "set pose" function. You have the notion of most of that already.
You said you has a pose, which I assume, it is an array position orientation, velocities and angular velocities for each rigid body. (Import: the pose must save the velocity of the state.
Most the time these are zero, but they must be set on each body, else the body will use the velocity already had in the instance.

What you are missing is missing is the part that also reset the joints states.
your pose must also contain the array of all the joints part of the contraction that you are assembling

I recently had similar situation training models with deep learning, each time I re start a model,
I had big problems with joint internal states,
Finally, I decided to fix that by adding the base functionality to the base joint.
ndJointBilateralConstraint::ClearMemory();

you use as follows, after you reset the bodies state,
you iterate over the joint also resting the joint state.
This will set all internal states to default values and recalculate the joint parameters.
here is the hinge example.
Code: Select all
void ndJointHinge::ClearMemory()
{
   ndMatrix matrix0;
   ndMatrix matrix1;
   CalculateGlobalMatrix(matrix0, matrix1);

   ndJointBilateralConstraint::ClearMemory();

   // save the current joint Omega
   const ndVector omega0(m_body0->GetOmega());
   const ndVector omega1(m_body1->GetOmega());

   // the joint angle can be determined by getting the angle between any two non parallel vectors
   m_angle = CalculateAngle(matrix0.m_up, matrix1.m_up, matrix1.m_front);
   m_omega = matrix1.m_front.DotProduct(omega0 - omega1).GetScalar();
   m_targetAngle = m_angle;
}


edit:
I just added the one for the double hinge. since you said you are using it.
Julio Jerez
Moderator
Moderator
 
Posts: 12425
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Initial conditions in joints

Postby blackbird_dream » Mon Sep 30, 2024 9:30 am

thks Julio. Let me some time to comprehend your code.

What you are missing ... your pose must also contain the array of all the joints part of the contraction that you are assembling

I don't understand this because it seems the way I've implemented it works fine. For example, in this video the right leg is initialized in a given pose with not-null angles:
https://www.youtube.com/watch?v=bNv6Z7pmGc0

in my subclass new_hingejoint I added a member ndFloat32 named m_offset.
In the constructor of the new_hingejoint I set targetangle (neutral angle for the spring damper) to m_offset:
Code: Select all
SetTargetAngle(m_offset);


In the method setlimits I changed:
Code: Select all
m_minLimit = minLimit + m_offset;
m_maxLimit = maxLimit + m_offset;

and in the getter:
Code: Select all
return  m_angle-m_offset;

what might be troublesome is that m_offset must be the relative offset of each joint, but the the biped has to be set in a pose with global offsets for every bodies, I mean in my example the foot has to be rotated to 50+20+20 prior to build the joint.
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby Julio Jerez » Mon Sep 30, 2024 6:17 pm

you can make a sub class, that's fine. It is ok to change limits and angles.
But trust me, it may seem it will work, but at some point, it will fail.

Even on that code, that you posted, there is an error. you are shifting the limits and the joint angle, by just adding the offset. that is fine,
however, there are other internal states, like the joint velocity, the joint target angle if you are using a PD.

In your class, you just call ClearMemory()
and it will rest the initial angle to zero. the joint speed to whatever the bodies say,
then you can rest the new limits as you wish.
and it all should be fine.

The code is very straight forward. check it out.

an analogy to that is say you are teleporting a rigid body, and you cool with a clever trick to rest position. them it seems it works, but after a while you keep getting weird effects.

That will be because the engine integrates the momentum and angular momentum, not the position and velocity.
So, resetting the position matrix, will ignore the global center of mass, the velocity and the angular velocity of the body. Same happen with joints.
Fortunattly this does not happen now because over the year I have fixed those issues, but those internal states are important and are library specific.
So my advice is to go but the library rules.
Julio Jerez
Moderator
Moderator
 
Posts: 12425
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Initial conditions in joints

Postby blackbird_dream » Tue Oct 01, 2024 4:11 am

ok Thks. There are several thing I don't understand.

  1. How to upgrade my ND4 version to get use of the clearmemory method? I just tried to copy and paste ndJointBilateralConstraint.cpp, ndJointBilateralConstraint.h, ndJointDoubleHinge.cpp, ndJointDoubleHinge.h, ndJointHinge.cpp and ndJointHinge.h
    and as expected the solution doesn't compile due to LNK2001 errors. Maybe I should run CMAKE again to build a new Newton engine, but I'm not sure it will work just replacing these 6 files. And just downloading the last build of Newton ( commit 009db3d), I'm not sure it will remains compatible with Dave's engine. Or maybe just regnerate the solution in Visual ?
  2. How to use it ? Do I need to keep my subclass to manage the shifts due to the angle offset, do I need to position all the bodies prior to build the joints and just call clearmemory in addition when I build each joint ? but when to call it ?
I'm sorry, you know I'm not so advanced in C++, my expertise is Mechanics.

PS : coming back to your msg, I already shifted the targetangle in my subclass and I checked that a PD controller is well handled because the rest position is shifted by the offset value, that is if the initial angle is let's say 50, the rest position is 0 and not 50. Concerning velocity, as the shift is constant the velocity should be unchanged, the shift is made at the construction of the joint with null velocity.
Last edited by blackbird_dream on Tue Oct 01, 2024 7:49 am, edited 1 time in total.
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby blackbird_dream » Tue Oct 01, 2024 4:39 am

What I read from your method clearmemory, it's like a reset:
at a desired current angular position of the joint, it sets the angle to zero ensuring continuity of internal forces and then no undesired acceleration. Am I correct ?
But that's not what I want to do. I just want to set the ragdoll in a given pose at t=0, which is not the null pose (null pose means here all joint angles are zero) and with null velocity.
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby Julio Jerez » Tue Oct 01, 2024 7:45 am

No it does not set the angle to zero.
It set to what ever the two boby relation is.
The only time the angle is set to zero is when the joint is created.

For example say, two bodies are linked by a hinge at any arbitrary pin.

At that point the joint angle is zero.

Then sat you make a pose where one body had the same orientation, but the second body is rotated 30 degrees around the pin.

After calling clear memory, the joint angle is set to 30 degrees. Not zero.
Julio Jerez
Moderator
Moderator
 
Posts: 12425
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Initial conditions in joints

Postby blackbird_dream » Tue Oct 01, 2024 7:54 am

No sorry, in fact it's not clear in my mind
but the second body is rotated 30 degrees around the pin.

What do you mean ?
How should I rotate it, I suspect it's not with NewtonBodySetMatrix. Maybe there is a demo illustrating this?

and finally you don't need all what I did with my subclass if the trick can be made with the method clearmemory ?
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby Julio Jerez » Tue Oct 01, 2024 10:19 am

You said you have a predefined pose.

What I understood is that you have a model that is rigged with joints. Usually this is done at a base pose.
Like a T or Davinchy stance.

The you want to set the model to a different pose like the strat of walk or the start or a run or something like that.
The initial pose is very different that the rig pose.
That what I mean a body is rotated.

If you set the model at that pose by setting only the matrices of the bodies, at the beginning the physics will generate huge joints acceleration.

This poses are usually generate by a person with some tool, or imported from some motion or animation.
That's what it looks to me you were doing in the video.

If not, the I misunderstood the entire question.
Julio Jerez
Moderator
Moderator
 
Posts: 12425
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Initial conditions in joints

Postby Julio Jerez » Tue Oct 01, 2024 10:22 am

Making the subclass is a good thing, I am just giving you a functionality that you might be missing.
Those two things are not exclusive of one another.
Julio Jerez
Moderator
Moderator
 
Posts: 12425
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Initial conditions in joints

Postby blackbird_dream » Tue Oct 01, 2024 10:35 am

Suppose my rigged pose is the T pose.
And I want to start the simulation (t=0) with arms along the body.
What I'm currently doing is to set all the limbs in the T pose except the arms that I rotate 90° (i.e along the body). At this stage there are no joints.
Then If I rig the ragdoll, the neutral position is the arms along the body. That's not what I want.
To correct this, I set the offset like i explained in my post while building the joints with my subclass. The results is the body at t=0 with the arms along the body and not in neutral position. And all accelerations are zero like in my video. You can see it's still. and if I set the spring and damper parameters to non null values the arms will rotate to the horizontal position as desired because the T pose is the rigged pose with this correction.

If you set the model at that pose by setting only the matrices of the bodies, at the beginning the physics will generate huge joints acceleration.
When I set the model at that pose there are no joints at this stage.
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby Julio Jerez » Tue Oct 01, 2024 11:56 am

I am very confused.

Are you saying that, you are making a system that uses different joints configuration for each pose?

My assumption is that you have a rig model, which is the same for any activity the rig will do.

Them each activity has its own initial condition.
So the goal is to figure out how to set the initial condition, such that the simulation step proceed as if it was starting from a T pose.
To me it is a bad sign, that you are changing the joint limits for each situation, if this was a human arm, I can't see a situation where the arm limit varies from activity to activity.

You can a lot in your subclass.

You are sub calling the joint, all the functionality is exposed to any sub calling, so you can easily implement what you want in the subclass.

If you look at the ikhinge, it does things to the joint and does not changes the base class.

Basically subclassing can be used to make special functions like motors.
Julio Jerez
Moderator
Moderator
 
Posts: 12425
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Initial conditions in joints

Postby blackbird_dream » Tue Oct 01, 2024 1:51 pm

You are perfectly right. What you say is what i wanna do.
But what i'm trying to say is that my subclass is just like a change of variable, nothing more.
The absolute arm boundaries never change. What changes is the change of variable depending on the ic.
User avatar
blackbird_dream
 
Posts: 379
Joined: Wed Jun 07, 2006 3:08 pm
Location: France

Re: Initial conditions in joints

Postby Julio Jerez » Tue Oct 01, 2024 2:40 pm

ok,
what you are doing is already closed to what the clear memory.

you can do two things.

1-if you want to try clear memory, see if Dave helps to integrate the later build.
I do not know how he does it.

2-you all variables are exposed to sub classes, you can just take the code,
and implement it in your sub class. the important part is when is calculate the angle.

and if you find that you do not need it,
you just lose one or two hours seen how the internal details work.

the fact that everything ex exposed to sub class, makes it easier to work, that hard part is to undesrand what is going on.
Julio Jerez
Moderator
Moderator
 
Posts: 12425
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Next

Return to General Discussion

Who is online

Users browsing this forum: No registered users and 4 guests