Friction works within bodies

Discussion in 'Simulation' started by wlorenz65, Jul 9, 2016.

  1. The balls remain in their bowls for 25 seconds when condim is 3.

    [​IMG]

    They immediately fall through when condim is 1.
     

    Attached Files:

  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    This is ultimately due to the contact softness, although there are several peculiar things about this model that need to be resolved first before we can get the the root cause:

    1. njmax=1000 is too small, and is some cases this limit is exceeded and any contacts or other constraints beyond the limit are automatically discarded. This triggers a warning, which is recorded in mjData and is printed in the console when using MuJoCo Pro, but HAPTIX does not have a console so warnings are silently ignored. I have been thinking of printing warnings over the 3d rendering for a while; apparently it is time to add this feature.

    2. The reason condim=3 slows down the penetration is that the ball is falling "between" the four meshes making up the bowl. So as it slides past them, there is tangential friction, which is not present with condim=1.

    3. This model is badly scaled, due to the geoms that are added far away from the center of each body (is there a reason to do this or is it just a test?) It is a legitimate model, but such scaling makes the underlying optimization problem harder, and you need a lot more iterations to achieve decent solver accuracy. Note that SolStat is log10(residual gradient), so we want this to be at least say -3, if not smaller. There is a plan to fine-tune the new large-scale solvers (CG and CGelliptic) to handle poor scaling, and I will actually save this model for later fine-tuning. But in general, if you see large values of SolStat, that means you are asking the solver to solve a hard optimization problem. You can increase the number of allowed iterations of course, but it is better to modify the model somehow.


    Now, to your original question: why is the ball falling through the bowl in the first place? Because the contact model is soft, and your model scale amplifies the effects of softness. Attached are two simple models that illustrate this: a ball falling on a cylinder. If you load both models, they will look the same but the ball will penetrate deeper in one of them. This is because all objects have been made smaller (and the visualizer is automatically scaling the view so you don't even see the difference in scale). Each model has a commented defaults section that reduces the penetration if you uncomment it. You can find an analysis of the steady-state penetration in this paper:

    http://homes.cs.washington.edu/~todorov/papers/TodorovICRA14.pdf

    Briefly, penetration depends on the solver parameters and gravity, but not on the object size or mass. So, if you fix the solver parameters and gravity, and make the objects smaller, the penetration will remain the same in absolute units, and therefore will look larger relative to the object size. Bottom line: avoid very small objects (or adjust the solver parameter to compensate... but better avoid very small objects).
     

    Attached Files:

    Kyokushin likes this.
  3. Isn't njmax=1000 the default setting in HAPTIX 1.31? It spreads its log file in every current directory, and there it complains about array bounds being too small. I found the default setting of nconmax=100 more problematic. Sometimes the log tells me to increase maxgeom, but this is only possible in MuJoCo Pro.

    I've tried to overlap the 4 meshes, so that there is no more zero-width gap "between" them where the ball can fall. It will then stay on the overlapping portion, but only if it is large enough. Something invisible makes the ball rotating so that it moves around.

    Why are there geoms far away from the center of the model? They stabilize the box in the middle. Some of the balls are rather heavy and the boxes would tip over.

    This model is just a test. The specification at http://electronicfilters.tpub.com/TM-10-4330-237-13P/css/TM-10-4330-237-13P_105.htm requests a standard torque of 9.5 Nm for a M8 nut made from the softest steel.

    A torque of 9.5 Nm applied to an M8 thread with a friction coefficient of 0.2 (unlubricated steel on steel) results in an axial clamp force of 6000 N. As I have it implemented now, those 6000 N are distributed among 6 contact balls within the nut, each of them smaller than 1 mm diameter. These are the little red balls from the model, and the bowl is the thread. But instead of 9.5 Nm, I can only apply a torque of 0.22 Nm, then the simulation gets unstable.

    Of course I could spread that 6000 N among more contact balls, but I don't want to pollute the contact space. So I was looking for a way to make those 6 contacts harder. To get a better understanding of how all these networked parameters in MuJoCo influence each other, I created this test model. I will adjust the solver parameter to compensate... as soon as I've found out which one.
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    Yes, the defaults are not large enough for every model, and need to be adjusted. There was an earlier attempt to set model-specific defaults automatically, but the problem is that there is no way for the compiler to know what the user intends to do with a given model, and the worst-case O(N^2) is usually too large. Good point about maxgeom, I will increase the predefined value in HAPTIX.

    The invisible force that makes the ball rotate is most likely due to the solver not converging within the allowed number of iterations, and generating inaccurate contact forces (the PGS-style solver is order-dependent and breaks symmetry). This should improve with future tuning of the CG-style solver.

    Re stabilizing boxes, good idea, but you can move them much closer. Also, maybe user spheres instead of boxes. No need to create 4 contact points per stabilizing object when you need just 1.

    To achieve maximum hardness, set solimp = (1,1,0) and solref = (0,1). These value are not actually allowed in simulation, but MuJoCo will clamp them internally to whatever is allowed. You will probably need a rather small time step for such a system.

    Keep in mind that MuJoCo is designed from the ground up for soft constraints. It is based on a mathematical framework which I have been developing for several years in the context of model-based optimization. If you are interested in the limit of hard contact (such as steel-steel) this may not be the right simulator for you -- and I don't know what is. If you look at the literature on contact modeling, you will notice that the hard-contact limit is poorly defined mathematically and gives rise to all kinds of paradoxes that make no physical sense. Things get particularly complicated with multiple simultaneous contacts. See this paper for a detailed explanation:

    http://ruina.tam.cornell.edu/research/topics/collision_mechanics/new_algebraic_rigid_body.pdf

    To model such phenomena accurately, you need to solve a stiff PDE at high spatial and temporal resolution, and rigid-body models cannot be expected to approximate its solution well. Still, it will be interesting to see how close you can get in MuJoCo.
     
    Kyokushin likes this.
  5. A timestep of 0.5 ms is enough to simulate hard steel-on-steel contacts. The solver is not the problem. It's a bug in the mesh collider that makes the Nuts and Bolts Task impossible for MuJoCo. When the robot loosens the nut with the wrench, the simulation will explode. When a sphere is sliding over a mesh and penetrates it, there are sawtooth-like spikes when it crosses a vertex. These spikes don't depend on the time step. They cause the contact normal to jump about 30°, and when high forces are involved, these normal jumps will cause a wave through the whole simulation and cause it to explode. Soft contacts are not the true solution, they are just masking the mesh collider bug.

    Another problem is when the sphere slides over the gap between two adjacent meshes which exists because MuJoCo doesn't have a concave mesh collider. There are two force normals then.

    I will make a video that explains the bug and upload it together with the Nuts and Bolts Task to the model section.
     
  6. Emo Todorov

    Emo Todorov Administrator Staff Member

    Yes, discrete jumps are unavoidable when using meshes. One solution is to increase the resolution of the mesh. Also, have you experimented with the MPR iter and MPR tol settings? They control the iterative mesh collision algorithm (called MPR). Larger number of iterations and smaller tolerance value will make the output of the collision detector more accurate. It will never be the same as a smooth analytical surface, but could improve things.