Refactoring joints

A place to discuss everything related to Newton Dynamics.

Moderators: Sascha Willems, walaber

Re: Self balancing biped

Postby Julio Jerez » Thu Jan 25, 2018 2:44 pm

I added all the cone joint, the third one is a motor that control all three dof.
no quiet a motor because the torque velocity is zero always, but I believe this is good enough to serve and the base for the dynamic rag doll.

The different is that now we only nee one joint that can support all joint variance, as oppose to before where each joints had its own implementation so it was hard to try different things.

I will proceed to re enable all other joint the rest of the week to see if we can get back into the inverse dynamics again.

edit:
Ok surrender.
The joint on the left use small angle an dteh one on the right use full angle and we can see the bug.
I try to enable the universal again, and here is total proof that small angular approximation brakes down in the present of even very small angles. for the to work the angle really has to be infinitesimal, even error of one degrees is enough to build up when commuting the order or rotations.
The joint simply wobbles and we know that joint work wit the old method. so that clue that the axis selection is wrong or the deviation of the instant news rotation angle is even more wrong.

what we should see is the joint bending with a fix angle generate by the gyro effect of having two rotations.

some how I am still hoping this is a very big bug, because I still refuse to believe the theory will fail so spectacularly.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby Julio Jerez » Thu Jan 25, 2018 5:07 pm

woohoo I think found the bug,
when I wrote the struct to control the axis I did it like t this
Code: Select all
   union
   {
      int m_mask;
      struct
      {
         int m_xAxis : 1;
         int m_yAxis : 1;
         int m_zAxis : 1;
         int m_rollAxis : 1;
         int m_yawAxis : 1;
         int m_pitchAxis : 1;
      };
   };


but the flag should be in order, like this
Code: Select all
   union
   {
      int m_mask;
      struct
      {
         int m_xAxis : 1;
         int m_yAxis : 1;
         int m_zAxis : 1;
         int m_pitchAxis : 1;
         int m_yawAxis : 1;
         int m_rollAxis : 1;
      };
   };


This could be really good. I will try again see if this fix it
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby JoeJ » Fri Jan 26, 2018 7:55 am

The right one looks fine, but the left one gains energy it seems. (probably in the moment when we see the red limit visualization begins to rotate. That's visible mostly when angular velocity is pretty low)

But this could be acceptable i guess. There is no flipping as before with the capsules :)

Edit: I just had the case where it was almost at rest and then started rotating at higher speed, so i'm sure it gains energy. But still acceptable if controllers can be still accurate enough and will stop this.
User avatar
JoeJ
 
Posts: 1494
Joined: Tue Dec 21, 2010 6:18 pm

Re: Self balancing biped

Postby Julio Jerez » Fri Jan 26, 2018 10:12 am

a few thing, gaining energy in one axis is correct. because as it loses spin energy along the principal spinning axis the precision rotation gain energy only to keep conservation of both energy and angular momentum, you can see a demonstration on thsi video.
https://www.youtube.com/watch?v=fv_AinDLHJY

Thsi is what made me excited and knew the derivatives are correct, when I run the Gyroscope an saw that gradually over time they try to align to vertically, while the top drops down because teh friction drain a long more energy when the top drift want around over the surface.

this is also part of whe it call teh middle axis there a spinning object will gradually align to one the principal axis with the larger angular momentum.

The problem with is selecting the axis of rotation, it is clear that the joint on the right because we get the twist axis, and the the other two are form by rotating the other tow around teh twist only wan of the tow axis align with he cone. So far this seem to be the only method to select axis system that does not suffer from gimbal lock and is orthogonal.
but he penalty is that you can no get a Cartesian de compotation of the Euler for defining limits.

teh huge but I discovered is fact made sense worse. it actually show me how wrong my method was so I am abandoning the small approximation method.

I am still going to give a shot and the limit. withe a simple diffrent method. and cna de decipoe liek this.

1-gettion the twist angle for the quaternion is very eassy, and we had that working fine.
we sa it is the motor joint and that does ever fail,
so basically step one is getting the twist angle and check limit on tha angle the isseu a row use the pin and the cpil angle.

he is teh hard part.
2-Get the cone angle and it is perpendicular axis.
here we can issue one or tow row along thso angle to correct any angle sine teh are orthognal.

how evet we cna do better. since the matrix formed by the twist, teh cone and it perpemdicular axis is ortogulan, we can calcular the roathion of teh two secun axis aroing the twist axis only the align wi ith the Yaw and Roll angle. the tow componend of that rotation and the cosine and the angel the we need to rotate the frame to satfi the clip error.

itis like say you wna to correct the linera position, and you knwo one is vertical, bu the ohorzonal is variable.

we has not problem using the three is any direction as long as there are mutually permendicular thjsi si whe we wnat to do with euler.
but we can do it in a different way. we can use teh vertical, and teh normalized the horizontal alone one direction and issue only one row, thsi has proven to be unstable sine it always happen that the object can move along the side, but can be made more stable by issuing a their row with zero acceleration. however is not always as good as using the Cartesian decomposition to clip linear error.

It seem the using angle teh method is teh other way around we nee to get the cone angle as teh reference frame. and here we can issue one row the correct error and the oerehis usually zero.

bu I claim we can do the oethe way fodn out what roation long teh towist match the yw and rall angles and these cosing diorection fo these angle are the clip error that reco e teh error along the cone axis system.

so basically it come down to get teh cone and do corewntion along teh cone and also along teh side of the cone.
I will try that tomorrow maybe that's is a better solution, at least we know that tah work when doing only teh cone correction.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby JoeJ » Fri Jan 26, 2018 10:41 am

I started to think the same as well, probably we gave up on twist / swing too fast. And maybe when i tried to make a motor from it, i forgot to add a 3th row for stabilization (but i doupt so).

One idea i have is that eventually we need to align one row to the long axis of the capsule (if we think of the ragdoll), which would handle the twist. I guess twist is most problematic. If this is necessary, maybe it is enough to constantly adapt a cone on this axis so it is inside the real limit cone defined in parent space. This inner cone would have an angle as large as possible, and maybe this lie to the IK system would not affect anything in practice. (But i fail to imagine properly)

Sounds partially similar to what you say - it's difficult to talk about that. :)
User avatar
JoeJ
 
Posts: 1494
Joined: Tue Dec 21, 2010 6:18 pm

Re: Self balancing biped

Postby Julio Jerez » Fri Jan 26, 2018 3:18 pm

Ok agree, les us work on the cone. I rertore the universal to work as it was before.

one thing that is remarkable and I kind of start having second thought is the effect of the
moving the angular derivative to the joints. doing that result in more realistic behavior but this also introduce lot on high no linearity to the integrator and can easy explode.

I committed two joints the one of the left do the old step when is force the error to be zero,
and the second on the right does by canceling the gyro torque such the net acceleration is zero.
to an untrained eye the joint on the left appear right, but in reality it is the joint on the right tah is correct.

If I trace the values angular momentum and angular energy for the joint on the right it all amounting value except the few frame at the beginning when ere the error is not zero and the joint apply acceleration to the orientation where the angular accel is zero and that is the tilt angle.

if I trace the value for the one on the right the entry remain constant but angular moment oscillate, in work space and is constant in local space.

only the one with the Tilt is cable to keep angular moment more of less contact on any orientation,
this is quite remarble result.
This is why this professor is so amassed and these effects.
https://www.youtube.com/watch?v=XPUuF_dECVI
See by the end who the Giro remain pointing at a fix direction regardless of what orientation he choses as e walk around. Maybe I made a demo to simulate that.

basically you can take a spinning object and if you want to generate a side torque you can just apply a perpendicular rotator with a motor and that will make the object tilt.
This is the base of inertial navigation systems.

you can do also the opposite, you can have a spinning disk is such way that the torques are zero. (the attachments pass by the center of mass) and
have a sensor measuring any angular rotation on the other two axis and this can e use to control the vehicle attitude. and that is the basic for inertia attitude control systems.

but boy is hard to simulate at high angular velocity. I hope we do not have to give it up.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby Julio Jerez » Sat Jan 27, 2018 8:27 pm

Ok Joe I committed the new joe model base of cone and twist angle.
I put two demos, one that is a plain simple cone with limit an dthe oethe is a motor with limit.
you can pick and drag to any position an so far seem stable and move in the desired direction.

I knwo I said thsi so many time an as sonn as I think I have an robust model I see the flaw.
I hope this at leats last longer.
any was I will leav the generic 6dof by I will no use as base class for all joint that was a big mistake.
I will just make sure all joint are using the same conevtion to get euler angles.

and I will use the ball and cicke a steh base class fo the Dynamics rag doll and inver dynamics joints.

if you have time please sync and check it out, please let me knwo is you see any problem.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby JoeJ » Sun Jan 28, 2018 4:25 am

I'll take a look later the day, but let me note some ideas i've had at night:

In my twist/swing there is an open question about aligning the twist row either to the parent or the child. Both worked equally well so i just used the average, but we could utilize this to make twist row as orthogonal as possible to other rows eventually.

We could try to use linear rows as well, e.g. use angular row just for the twist and handle swing with two linear rows (which makes sense if we imagine muscle anatomy). I tried something like this in the past but got jitter - but i think it should work. (I also think the idea is similar as your order independent small angles because it turns shear into rotation, but is more intuitive and less error prone to implement.)
User avatar
JoeJ
 
Posts: 1494
Joined: Tue Dec 21, 2010 6:18 pm

Re: Self balancing biped

Postby JoeJ » Sun Jan 28, 2018 11:21 am

I tried the new demo now, looks good but i wondered the joints have chaotic behavior if you stress them a little (pulling appart or violating a limit just a bit).
I looked at the code, but found nothing wrong - disabled both twist and swing so only ball socket remains - better but still chaotic.

Then i used an older version of joints demo to bring back my own limit joint which i remembered to work well. But it behaves chaotic even when not interacting with the mouse (It bounces at the cone limit. My setup was horizontal so this happens all the time.)
I made solver model 2 and also made it independent of dCustomJoint, but still broken.
If i remove limits and make it just ball socket (also setting 3 rows count in constructor), it seems ok when passive but when pulling appart it behaves very chaotic even with model 2.

I can not remember exactly how pulling effected joints with older versions, but the fact my limit joint does not work anymore makes me think something with joints is wrong since some unknown time.
(I always used those pulling and stressing tests - if the joint becomes a perpetuum mobile, i conclude i did something wrong. But now you can easily turn every joint into that.)

I do not know how to reproduce this in a meaningful way yet, and i could be just wrong. But if not all your current effort on joint design is affected.

Ah - maybe it has to do with this:
Julio Jerez wrote:one thing that is remarkable and I kind of start having second thought is the effect of the
moving the angular derivative to the joints. doing that result in more realistic behavior but this also introduce lot on high no linearity to the integrator and can easy explode.
:?:
User avatar
JoeJ
 
Posts: 1494
Joined: Tue Dec 21, 2010 6:18 pm

Re: Self balancing biped

Postby Julio Jerez » Sun Jan 28, 2018 2:22 pm

can you past your test in the demos so that I can test it.

I has seen that behavior but I believe this is normal for a ball joint if is pull with the mouse.
what worries me more is the behavior with the joint hit the limit.

the were the derivative is not playing nice. I just saw when re writing the slider.
each time it hit the bounds it bounced back we a really strong acceleration.
so I was able to fix that is the joint callback.
I will do teh same technique to the hinge and also to the ball an socket.

use the derivative and clipping the force made the joint stronger by seem not to work well at the limits.

anyway of you can paste you test that show the problem in the demos I can see what you mean better.
there is a way to reproduce picking in the demo now.
in file ..\demosSandbox\sdkDemos\DemoCameraManager.cpp line 138

1- line 138 change the #if 0 to #if 1
2- line 147 chnage the #if 0 to #if 1
3- make sure the demo start playing the demo you are debugging
4- rund the demo until you can reproduce the bug you want
5- go back to line line 147 change the #if 1 to #if 0
6- not iof you rund the demo it will replay the mouse picking events.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby JoeJ » Sun Jan 28, 2018 2:45 pm

Julio Jerez wrote:can you past your test in the demos so that I can test it.


That means bring back old things you already fixed (e.g. my code does not submit some rows in special cases which is wrong but unlikely the reason).
But you can do it temproary. I've renamed the joint, so you can just copy paste the code below and add this:

AddJoesLimitJoint (scene, dVector(-24.0f, 0.0f, -15.0f));

You will get a crash because your demo framework assumes every user joint subclasses dCustomJoint. I disabled the debug vis to get around that.

When you start the demo, the 'arm' behaves a bit bouncy, but if you pick and let it fall down again, it may bounce around for a very long time.


:!: Before you do this, try to rotate your own 2-capsule-limit-setup 90 degrees so gravity pulls the capsules to the limit, or simply rotate gravity direction. You might see the same issues with your own joint. (just a guess)


Code: Select all
struct JoesNewRagdollJoint
{
   dMatrix m_localMatrix0;
   dMatrix m_localMatrix1;
   void* m_userData;
   NewtonBody* m_body0;
   NewtonBody* m_body1;
   NewtonJoint* m_joint;
   NewtonWorld* m_world;


   dQuaternion m_target; // relative target rotation to reach at next timestep

   // motor:
   dFloat m_reduceError;
   dFloat m_pin_length;
   dFloat m_angularFriction;
   dFloat m_stiffness;

   dFloat m_anim_speed;
   dFloat m_anim_offset;
   dFloat m_anim_time;

   // limits:
   bool m_isLimitJoint;

   dFloat m_minTwistAngle;
   dFloat m_maxTwistAngle;

   dFloat m_coneAngle;
   dFloat m_arcAngleCos;
   dFloat m_arcAngleSin;

   
   JoesNewRagdollJoint(NewtonBody* child, NewtonBody* parent, const dMatrix &localMatrix0, const dMatrix &localMatrix1, NewtonWorld *world, bool isLimitJoint = false)
   {
      m_joint = NULL;
      m_body0 = child;
      m_body1 = parent;

      m_world   = m_body0 ? NewtonBodyGetWorld (m_body0) : NewtonBodyGetWorld (m_body1);
      m_joint = NewtonConstraintCreateUserJoint (m_world, 6, SubmitConstraintsCallback, m_body0, m_body1);

      NewtonJointSetUserData (m_joint, this);

      m_localMatrix0 = localMatrix0;
      m_localMatrix1 = localMatrix1;

      m_target = dQuaternion(dVector(1.0f, 0, 0), 0.0f);
      m_reduceError = 0.95f; // amount of error to reduce per timestep (more -> oszillation)
      m_stiffness = 0.98f;
      m_angularFriction = 300.0f;

      m_anim_speed = 0.0f;
      m_anim_offset = 0.0f;
      m_anim_time = 0.0f;
      
      m_isLimitJoint = isLimitJoint;

      SetTwistSwingLimits (0.1f, 0.2f, -0.1f, 0.1f);
      //SetTwistSwingLimits (0.1f, 0.0f, -0.1f, 0.1f);
   }

   void SetTwistSwingLimits (const float coneAngle, const float arcAngle, const float minTwistAngle, const float maxTwistAngle)
   {
      float const maxAng = 2.8f; // to prevent flipping on the pole on the backside

      m_coneAngle = min (maxAng, coneAngle);
      float angle = max (0.0f, min (maxAng, arcAngle + m_coneAngle) - m_coneAngle);
      m_arcAngleCos = cos (angle);
      m_arcAngleSin = sin (angle);

      m_minTwistAngle = minTwistAngle;
      m_maxTwistAngle = maxTwistAngle;
   }

   dVector BodyGetPointVelocity(const NewtonBody* const body, const dVector &point)
   {
      dMatrix matrix;
      dVector v(0.0f);
      dVector w(0.0f);
      dVector c(0.0f);
      NewtonBodyGetVelocity(body, &v[0]);
      NewtonBodyGetOmega(body, &w[0]);
      NewtonBodyGetMatrix(body, &matrix[0][0]);
      c = matrix.m_posit; // TODO: Does not handle COM offset !!!
      return v + w.CrossProduct(point - c);
   }

   static void SubmitConstraintsCallback (const NewtonJoint* const userJoint, dFloat timestep, int threadIndex)
   {
      JoesNewRagdollJoint *joint = (JoesNewRagdollJoint*) NewtonJointGetUserData (userJoint);
      joint->SubmitConstraints(timestep, threadIndex);
   }

   void SubmitConstraints(dFloat timestep, int threadIndex)
   {
      dFloat invTimestep = 1.0f / timestep;

      dMatrix matrix0;
      dMatrix matrix1;

      //CalculateGlobalMatrix(matrix0, matrix1);
      dMatrix body0Matrix;
      // Get the global matrices of each rigid body.
      NewtonBodyGetMatrix(m_body0, &body0Matrix[0][0]);

      dMatrix body1Matrix (dGetIdentityMatrix());
      if (m_body1) {
         NewtonBodyGetMatrix(m_body1, &body1Matrix[0][0]);
      }
      matrix0 = m_localMatrix0 * body0Matrix;
      matrix1 = m_localMatrix1 * body1Matrix;



      const dVector& p0 = matrix0.m_posit;
      const dVector& p1 = matrix1.m_posit;
      NewtonUserJointAddLinearRow (m_joint, &p0[0], &p1[0], &matrix0.m_front[0]);
      NewtonUserJointAddLinearRow (m_joint, &p0[0], &p1[0], &matrix0.m_up[0]);
      NewtonUserJointAddLinearRow (m_joint, &p0[0], &p1[0], &matrix0.m_right[0]);



      if (m_isLimitJoint)
      {

         //dCustomBallAndSocket::SubmitConstraints(timestep, threadIndex);


         const dVector& coneDir0 = matrix0.m_front;
         const dVector& coneDir1 = matrix1.m_front;
         float dot = coneDir0.DotProduct3(coneDir1);
         if (dot < -0.999) return; // should never happen

         // do the twist

         if (m_maxTwistAngle >= m_minTwistAngle) // twist restricted?
         {
            dQuaternion quat0(matrix0), quat1(matrix1);     
            float *q0 = (float*)&quat0;
            float *q1 = (float*)&quat1;

            // factor rotation about x axis between quat0 and quat1. Code is an optimization of this: qt = q0.Inversed() * q1; halfTwistAngle = atan (qt.x / qt.w);
            float twistAngle = 2.0f * atan (
               ( ( ( (q0[0] * q1[1]) + (-q0[1] * q1[0]) ) + (-q0[2] * q1[3]) ) - (-q0[3] * q1[2]) ) /
               ( ( ( (q0[0] * q1[0]) - (-q0[1] * q1[1]) ) - (-q0[2] * q1[2]) ) - (-q0[3] * q1[3]) ) );

            // select an axis for the twist - any on the unit arc from coneDir0 to coneDir1 would do - average seemed best after some tests
            dVector twistAxis = coneDir0 + coneDir1;
            twistAxis.Scale (1.0f / sqrt (twistAxis.DotProduct3(twistAxis)));

            if (m_maxTwistAngle == m_minTwistAngle) // no freedom for any twist
            {
               NewtonUserJointAddAngularRow (m_joint, twistAngle - m_maxTwistAngle, (float*)&twistAxis);
            }
            else if (twistAngle > m_maxTwistAngle)
            {
               NewtonUserJointAddAngularRow (m_joint, twistAngle - m_maxTwistAngle, (float*)&twistAxis);
               NewtonUserJointSetRowMinimumFriction (m_joint, 0.0f);
            }
            else if (twistAngle < m_minTwistAngle)
            {
               NewtonUserJointAddAngularRow (m_joint, twistAngle - m_minTwistAngle, (float*)&twistAxis);
               NewtonUserJointSetRowMaximumFriction (m_joint, 0.0f);
            }
         }

         // do the swing
#if 0
         // simple cone limit:

         float angle = acos (dot) - m_coneAngle;
         if (angle > 0)
         {
            dVector swingAxis = (coneDir0.CrossProduct(coneDir1));
            swingAxis.Scale (1.0 / sqrt (swingAxis.DotProduct3(swingAxis)));
            NewtonUserJointAddAngularRow (m_joint, angle, (float*)&swingAxis);
            NewtonUserJointSetRowMinimumFriction (m_joint, 0.0);
         }
#else
         // cone / arc limit - think of an piece of pizza (arc) and an allowed max distance from it (cone):

         if (m_coneAngle > 0.0f && dot < 0.999f)
         {
            // project current axis to the arc plane (y)
            dVector d = matrix1.UnrotateVector (matrix0.m_front);
            dVector cone = d; cone.m_y = 0; cone.Scale (1.0f / sqrt (cone.DotProduct3(cone)));

            // clamp the result to be within the arc angle
            if (cone.m_x < m_arcAngleCos)
               cone = dVector (m_arcAngleCos, 0.0f, ( (cone.m_z < 0.0f) ? -m_arcAngleSin : m_arcAngleSin));

            // do a regular cone constraint from that
            float angle = acos (max(-1.0f, min(1.0f, d.DotProduct3(cone)))) - m_coneAngle;
            if (angle > 0.0f)
            {
               dVector swingAxis = matrix1.RotateVector(d.CrossProduct(cone));
               swingAxis.Scale (1.0f / sqrt (swingAxis.DotProduct3(swingAxis)));
               NewtonUserJointAddAngularRow (m_joint, angle, (float*)&swingAxis);
               NewtonUserJointSetRowMinimumFriction (m_joint, 0.0f);
            }   
         }
#endif
      }
      else
      {

         if (m_anim_speed != 0.0f) // some animation to illustrate purpose
         {
            m_anim_time += timestep * m_anim_speed;
            dFloat a0 = sin(m_anim_time);
            dFloat a1 = m_anim_offset * 3.14f;
            dVector axis(sin(a1), 0.0f, cos(a1));
            //dVector axis (1,0,0);
            m_target = dQuaternion(axis, a0 * 0.5f);
         }

         // measure error
         dQuaternion q0(matrix0);
         dQuaternion q1(matrix1);
         dQuaternion qt0 = m_target * q1;
         dQuaternion qErr = ((q0.DotProduct(qt0) < 0.0f)   ? dQuaternion(-q0.m_q0, q0.m_q1, q0.m_q2, q0.m_q3) : dQuaternion(q0.m_q0, -q0.m_q1, -q0.m_q2, -q0.m_q3)) * qt0;
         qErr.Normalize();

         dFloat errorAngle = 2.0f * acos(dMax(dFloat(-1.0f), dMin(dFloat(1.0f), qErr.m_q0)));
         dVector errorAngVel(0, 0, 0);

         dMatrix basis;
         if (errorAngle > 1.0e-10f) {
            dVector errorAxis(qErr.m_q1, qErr.m_q2, qErr.m_q3, 0.0f);
            errorAxis = errorAxis.Scale(1.0f / dSqrt(errorAxis.DotProduct3(errorAxis)));
            errorAngVel = errorAxis.Scale(errorAngle * invTimestep);

            basis = dGrammSchmidt(errorAxis);
         } else {
            basis = dMatrix(qt0, dVector(0.0f, 0.0f, 0.0f, 1.0f));
         }

         dVector angVel0(0.0f);
         dVector angVel1(0.0f);
         NewtonBodyGetOmega(m_body0, (dFloat*)&angVel0);
         NewtonBodyGetOmega(m_body1, (dFloat*)&angVel1);

         dVector angAcc = (errorAngVel.Scale(m_reduceError) - (angVel0 - angVel1)).Scale(invTimestep);

         //dCustomBallAndSocket::SubmitConstraints(timestep, threadIndex);
         // motors
         for (int n = 0; n < 3; n++) {
            // calculate the desired acceleration
            dVector &axis = basis[n];
            dFloat relAccel = angAcc.DotProduct3(axis);

            NewtonUserJointAddAngularRow(m_joint, 0.0f, &axis[0]);
            NewtonUserJointSetRowAcceleration(m_joint, relAccel);
            NewtonUserJointSetRowMinimumFriction(m_joint, -m_angularFriction);
            NewtonUserJointSetRowMaximumFriction(m_joint, m_angularFriction);
            NewtonUserJointSetRowStiffness(m_joint, m_stiffness);
         }

      }
   }
};


void AddJoesLimitJoint (DemoEntityManager* const scene, const dVector& origin)
{
   NewtonBody* shoulder =   CreateBox (scene, origin + dVector (-0.5f,  2.0f, 0.0f, 0.0f), dVector (0.5f,  0.5f, 0.5f, 0.0f));
   NewtonBodySetMassMatrix (shoulder, 0,0,0,0);
   NewtonBody* bicep =      CreateBox (scene, origin + dVector ( 0.0f,  2.0f, 0.0f, 0.0f), dVector (1.0f,  0.25f, 0.25f, 0.0f));
   NewtonBody* arm =      CreateBox (scene, origin + dVector ( 1.0f,  2.0f, 0.0f, 0.0f), dVector (1.0f,  0.2f, 0.2f, 0.0f));

   dMatrix localMatShoulder0 = dGetIdentityMatrix(); localMatShoulder0.m_posit = dVector (0.25f, 0.0f, 0.0f, 1.0f);
   dMatrix localMatShoulder1 = dGetIdentityMatrix(); localMatShoulder1.m_posit = dVector (-0.5f, 0.0f, 0.0f, 1.0f);

   dMatrix localMatBicep0 = dGetIdentityMatrix(); localMatBicep0.m_posit = dVector (0.5f, 0.0f, 0.0f, 1.0f);
   dMatrix localMatBicep1 = dGetIdentityMatrix(); localMatBicep1.m_posit = dVector (-0.5f, 0.0f, 0.0f, 1.0f);
   /*{
      dMatrix rotation =  dPitchMatrix(randF(bodyIndex*3+0) * M_PI * 0.25f * randomness);
      rotation = rotation * dYawMatrix(randF(bodyIndex*3+1) * M_PI * 0.25f * randomness);
      rotation = rotation * dYawMatrix(randF(bodyIndex*3+2) * M_PI * 0.25f * randomness);
      matrix0 = matrix0 * rotation;
   }*/
   JoesNewRagdollJoint* ellbowJoint = new JoesNewRagdollJoint (arm, bicep, localMatBicep1, localMatBicep0, scene->GetNewton(), true);
   NewtonUserJointSetSolverModel (ellbowJoint->m_joint, 2);
   JoesNewRagdollJoint* shoulderJoint = new JoesNewRagdollJoint (bicep, shoulder, localMatShoulder1, localMatShoulder0, scene->GetNewton(), true);
   NewtonUserJointSetSolverModel (shoulderJoint->m_joint, 2);
}
User avatar
JoeJ
 
Posts: 1494
Joined: Tue Dec 21, 2010 6:18 pm

Re: Self balancing biped

Postby Julio Jerez » Sun Jan 28, 2018 4:19 pm

Ok I see it really bad, I made to cubclass for the dCustom joint.
and yes is is very bad,
are you say thsi was stable before?

what I will do is that I will test it in older version before we start all of this, and see wher thongs when so wrong.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby JoeJ » Sun Jan 28, 2018 4:24 pm

Yes it worked well with the same settings, no bouncing - sure of that.
(i'm unsure only about how ball socket behaved when pulled apart.)
User avatar
JoeJ
 
Posts: 1494
Joined: Tue Dec 21, 2010 6:18 pm

Re: Self balancing biped

Postby Julio Jerez » Sun Jan 28, 2018 4:51 pm

ok that show that some when really wrong at some point.
I will start form what was commented on December 31 and add the teh bug fixes and othe thong that where added and the start form there.

It is obvious that some is quite incorrect.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

Re: Self balancing biped

Postby Julio Jerez » Sun Jan 28, 2018 7:27 pm

Oh Joe I am really glad you are helping me to verify teh work,
I downloaded the SDK that was labeled on Dec 31.

and the first thing I did was to simple copy you test and running.
I can see the joint acting way more stable, but is no toally rigid, it does separate a little.
I beleive tshi si hwo the engine works. when separation happens the game try to recover wieth a contact velocity.
I will commited the code liek this, by I have to first add the bug fixed and the project changes

and it will be like is was Dec 31.

Maybe you cna check is you recognized teh behavior at that point before moving on again.
Julio Jerez
Moderator
Moderator
 
Posts: 12480
Joined: Sun Sep 14, 2003 2:18 pm
Location: Los Angeles

PreviousNext

Return to General Discussion

Who is online

Users browsing this forum: No registered users and 1 guest