Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Setting frictionloss breaks joint equality constraint #2430

Closed
2 tasks done
jjyyxx opened this issue Feb 17, 2025 · 8 comments
Closed
2 tasks done

Setting frictionloss breaks joint equality constraint #2430

jjyyxx opened this issue Feb 17, 2025 · 8 comments
Labels
bug Something isn't working

Comments

@jjyyxx
Copy link
Contributor

jjyyxx commented Feb 17, 2025

Intro

Hi!

I am a graduate student at HKU, I use MuJoCo for my research on robotic manipulation.

My setup

MuJoCo 3.2.7, Python and C, Linux

What's happening? What did you expect?

I apologize if this issue falls more under the current limitations of constraint optimization rather than being a bug.

When using equality/joint to couple two joints A and B (e.g., with polycoef="0 1"), the expectation is that both joints should move in sync. If a passive/actuator/applied force is applied to prevent joint B from moving, joint A should also stop. However, an issue arises when the force is implemented via frictionloss on joint B.

In such cases:

  • With small frictionloss, joint B starts to lag behind.
  • With large frictionloss, joint B completely stops moving while joint A moves almost freely.

Since frictionloss is implemented as constraints, this behavior might indicate an issue with the constraint solution. Interestingly, other constraint forces like contact forces seem to perform as expected.

For further context and to avoid potential "XY problem," the documentation mentions:

(Joint equality) Coupling of two joints is useful for modeling helical joints.

While it is straightforward to create a basic helical joint using a slide and a hinge with joint equality, I am experimenting with achieving self-locking. Specifically, I want the force applied to the slide (such as gravity and normal force) to not cause any movement in both the slide and the hinge, only to prevent potential movement. I would appreciate any insights or solutions that might address this issue.

Steps for reproduction

See XML

Minimal model for reproduction

<?xml version="1.0" encoding="utf-8"?>
<mujoco model="equal">
  <compiler angle="radian"/>

  <option
    timestep="0.001" integrator="implicit"
    noslip_iterations="5"
    cone="elliptic" impratio="10"
  />

  <default>
    <geom condim="1" />
  </default>

  <worldbody>
    <geom type="plane" size="0.5 0.5 0.025" pos="0 0 -0.1"/>

    <body name="1" gravcomp="0">
        <joint name="A" type="hinge" pos="0 0 0" axis="0 0 1" range="0 6.28" />
        <joint name="B" type="slide" pos="0 0 0" axis="0 0 1" range="0 1" />  <!-- frictionloss="100000" -->
        <geom name="1" type="cylinder" size="0.1 0.1" pos="0 0 0" rgba="1 0 0 0.5" />
        <site name="1" pos="0 0.1 0" rgba="0 1 0 1"/>
    </body>

    <!-- Contact force example -->
    <!-- <body name="2" pos="0 0 0.2">
        <joint name="2" type="slide" pos="0 0 0" axis="0 0 1" range="-0.1 1" />
        <geom name="2" type="cylinder" size="0.1 0.01" pos="0 0 0" rgba="1 0 0 0.5" density="1000000" />
    </body> -->
  </worldbody>

  <equality>
    <joint joint1="A" joint2="B" polycoef="0 200"/>
  </equality>

  <actuator>
    <position joint="A" ctrlrange="0 8" kp="10" kv="1"/>
    <!-- actuator force example -->
    <!-- <motor joint="B" ctrllimited="true" ctrlrange="-10000 10000" /> -->
  </actuator>

</mujoco>

Code required for reproduction

No response

Confirmations

@jjyyxx jjyyxx added the bug Something isn't working label Feb 17, 2025
@yuvaltassa
Copy link
Collaborator

You have two forces fighting each other, one is going to win. Equality constraints, like all constraints in MuJoCo, are soft. You can make them harder if you wish using solimp/solref.

@jjyyxx
Copy link
Contributor Author

jjyyxx commented Feb 17, 2025

@yuvaltassa Thanks for your quick response! I understand that all constraints in MuJoCo are soft, and have tried setting solref/solreffriction before posting the issue, but does not receive satisfactory results. My concerns are:

  1. The documentation says "(Active constraint) types are: equality, friction loss, limit, contact. Limits are handled as frictionless contacts by the solver and are not treated as a separate type internally." In my test, (joint) equality works reasonably well with limit and contact (joints stop moving when limit is reached, and overcomes the contact forces before moving). In these cases, no constraints show noticable violation on both sides. But when working with friction loss, adjusting solreffriction does not help, and adjusting equality/joint/solref requires reducing the timestep and solref to 0.0001 for reasonably small violation, which is unacceptable in terms of simulation efficiency.
  2. frictionloss="10000" upper bounds the friction force to 10000N, but replacing it with a 10000N or even larger constant force removes the violation. I know that smooth and constraint calculation happen in different solver stages, but I feel something could do better here.
  3. Could you kindly provide some suggestion about my actual problem mentioned in the issue: how to enforce self-locking in a helical joint?

    Specifically, I want the force applied to the slide (such as gravity and normal force) to not cause any movement in both the slide and the hinge, only to prevent potential movement.

@jjyyxx
Copy link
Contributor Author

jjyyxx commented Feb 18, 2025

@yuvaltassa I find that, while it is indeed related to soft constraints, the thing actually makes the phenomenon counterintuitive might be the noslip solver. In the noslip postprocessing step, the qfrc_constraint for the DOF with frictionloss is set to (near) zero, while the other DOF's qfrc_constraint is untouched, which completely breaks the equality constraint (thus not appeared as a "soft" violation).

Understanding this, it is easy to construct a funny example that when you apply force on one body, it stays in place, while the other starts to move (both body have one joint of x slide, and coupled):

Initial Perturb
Image Image

Is it possible to have better noslip mechanism? I find that while slip of contact friction is possible to prevent with impratio and solreffriction, the only way to stop slipping under pure dry friction is to enable noslip, which in turn leads to unexpected behavior above.

@yuvaltassa
Copy link
Collaborator

Can you please send your minimal "funny example"? This looks valuable...

@jjyyxx
Copy link
Contributor Author

jjyyxx commented Feb 18, 2025

Here it is. Move actuator 0 to left bound to see the effect. The larger the frictionloss and ctrlrange[0] are, the more obvious the displacement is. I have to say that, from my current understanding, MuJoCo currently does nothing wrong and works as expected. But it is just a bit counterintuitive, and potentially, the noslip solver could work with the rest of the constraint model better.

<?xml version="1.0" encoding="utf-8"?>
<mujoco>
  <compiler angle="radian" />
  <option timestep="0.001" integrator="implicit" noslip_iterations="1" />
  <worldbody>
    <geom name="plane" type="plane" size="0.5 0.5 0.025" pos="0 0 -0.15" />
    <body name="1">
      <joint name="1" type="slide" axis="1 0 0" frictionloss="100000" />
      <geom name="1" type="sphere" size="0.1" rgba="1 0 0 1" />
    </body>
    <body name="2" pos="0 0.5 0">
      <joint name="2" type="slide" axis="1 0 0" />
      <geom name="2" type="sphere" size="0.1" rgba="0 1 0 1" />
    </body>
  </worldbody>
  <equality>
    <joint joint1="1" joint2="2" polycoef="0 1" />
  </equality>
  <actuator>
    <motor joint="1" ctrlrange="-30000 0" />
  </actuator>
</mujoco>

P.S.: For the specific case of applying and overcoming large friction force on light bodies, I could think of applying large armature as a reasonable workaround.

@yuvaltassa
Copy link
Collaborator

Yes I played with this and see what is happening. Your diagnosis is correct, this is basically due to how noslip is implemented. As far as I know there is no way (even in principle) to merge say the full PGS solve with a noslip step (rather than making it an additional solve). So I currently don't see a way to avoid it...

@jjyyxx
Copy link
Contributor Author

jjyyxx commented Feb 24, 2025

@yuvaltassa Thank you for the information. May I ask if #2423 has the same root cause or not?

@yuvaltassa
Copy link
Collaborator

Ah missed that one. I hope to look more closely later in the week, will let you know.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

2 participants