possible invalid force/frame when using mj_get_contacts

Discussion in 'HAPTIX' started by Carensac, Mar 14, 2016.

  1. I’m having some problems when using the mj_get_contacts() from the mujoco Haptix API.
    My problem is that either the force or the frame seems to be false. I add to this post my current situation.
    On the image we can see the current state of the simulation as seen in the haptix gui. We can see 4 contact points on the left foot and 2 on the right one. I also have printed the results I get from the mjContacts structure after using mj_get_contacts().
    If we look at the contacts at the front of the left foot we can see oblique forces in the gui but the result from the mjContacts indicate nearly pure vertical forces (>300 on the first axis of the frame which is 0 0 1, and the 5th contact that doesn't have a z axis component in the mjContacts).

    So I’m wondering if I didn’t use the data from mjContacts correctly (especially the frame data) or if there is really a problem with the data itself…


    Here are the values from the mjContacts structure.
    Bodies // position // force // frame
    0::10 // -0.0903123 -0.259336 -0.000527503 // 0 0 0 // 0 0 1 0 1 0 -1 0 0 //
    0::10 // -0.0403124 -0.259441 -0.000519373 // 0 0 0 // 0 0 1 0 1 0 -1 0 0 //
    0::10 // -0.0900074 -0.114336 -0.000520186 // 319.92 0 0 // 0 0 1 0 1 0 -1 0 0 //
    0::10 // -0.0400075 -0.114442 -0.000512055 // 339.294 0 30.3053 // 0 0 1 0 1 0 -1 0 0 //
    0::14 // 0.0404721 0.172338 -7.76526e-005 // 0 124.528 38.6311 // 0 0 1 0 1 0 -1 0 0 //
    0::14 // 0.090471 0.17224 -0.000232572 // 76.0198 27.5704 58.0195 // 0 0 1 0 1 0 -1 0 0 //

    [​IMG]
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    Interesting. Could you go back to that situation and press Ctrl+P (Print Data from the File Menu)? This will generate the file MJDATA.TXT in the program directory -- which is a core dump of the entire MuJoCo workspace. I want to see if the contact frames and forces there agree with the output of the socket API. The CONTACT section in that file describes all the active contacts and provides efc_adresses ("efc" stands for equality-fiction-contact and refers to all constraints). The indices are addresses in the EFC_FORCE vector of constraint forces... Anyway, just send me the MJDATA.TXT file.

    Also, have you noticed such discrepancies when the simulation is running, or only when it is paused?

    Also, which solver are you using? Some of them construct friction pyramids while others use elliptic friction cones (although the socket API is supposed to convert to 3D force and hide this detail from you).
     
  3. Here is the file. Seems to contains the same values as the one in the mjContacts (I guess that the 3 values between the forces are the ones for the friction torques).
    To obtain those results I just use the default, so euler and pyramidal, parameters (except that I use condim=”4” for all the rigid bodies). I use the mj_step function to progress and the result we see is the first step of the simulation.
    Switching to elliptic solves the problem (we can see that the force read in the mjContacts are now oblique)

    OK, I found something pretty strange.
    If I use the pyramidal and do one mj_step(). Then, with the simulation paused I switch between elliptic and pyramidal. When I select pyramidal I see the oblique forces but when I select elliptic I see the forces corresponding to the data from the mjContacts (I’ll put a screen).
    If I start with elliptic then do one mj_step(). This time I see the oblique forces when selecting elliptic and vertical forces when selecting pyramidal (though the vertical forces are different from the one after one step with the pyramidal solver which is normal).

    So I guess the problem is that when using pyramidal before doing mj_step() the gui inverse the forces it shows between the pyramidal and elliptic solver (which would be a pretty strange bug^^).

    Result with elliptic:
    Bodies // position // force // frame
    0::10 // -0.0900005 -0.254594 -0.00112835 // 0 0 0 // 0 0 1 0 1 0 -1 0 0 //
    0::10 // -0.0400006 -0.254686 -0.00110853 // 0 0 0 // 0 0 1 0 1 0 -1 0 0 //
    0::10 // -0.089734 -0.109595 -0.000791036 // 325.246 325.103 8.72685 // 0 0 1 0 1 0 -1 0 0 //
    0::10 // -0.0397341 -0.109687 -0.000771216 // 408.559 408.318 12.7158 // 0 0 1 0 1 0 -1 0 0 //
    0::14 // 0.041091 0.173115 -8.09089e-005 // 229.458 -228.987 -5.14516 // 0 0 1 0 1 0 -1 0 0 //
    0::14 // 0.09109 0.173055 -0.00023952 // 411.959 138.84 34.599 // 0 0 1 0 1 0 -1 0 0 //

    Here is the screen when starting with pyramidal and selecting elliptic with the simulation paused.
    [​IMG]
     

    Attached Files:

  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    What a mess, thank you for uncovering it! Turns out there is one bug and one design flaw, and they interact with each other:

    (bug) The socket API just copies the contact force as if it is always in the elliptic cone representation, and ignores the fact that it may be in the pyramid cone representation which needs to be decoded first. The decoding function is there and is being called everywhere else, but I forgot to call it in the socket API.

    (design flaw) In paused mode the physics simulation does not run. However, the user can change the options, which in turn affects how the results from the last physics simulation are being interpreted (in particular, elliptic vs. pyramidal cone representation). The solution is to trigger a physics update in paused mode whenever the user touches the Physics Options dialog.

    Both are trivial to fix, and will be done in version 1.3 to be released around the end of March. In the meantime, stick to the elliptic solver and everything will be consistent.