Disable collisions for specific bodies at run-time

Discussion in 'Priority support' started by rafaelp, Jul 1, 2019.

  1. I need to disable collision checking for specific bodies in my simulation at run-time.

    I am aware that you can disable collisions of a particular geom by setting either its conaffinity or contype to 0 in the XML model.

    Is there a way to disable collision checking for a specific geom/body at run-time through the C API?

    Edit 1:

    It looks like there is this function that looks relevant:

    extern mjfConFilt mjcb_confilter;
    This callback can be used to replace MuJoCo's default collision filtering. When installed, this function is called for each pair of geoms that have passed the broad-phase test (or are predefined geom pairs in the MJCF) and are candidates for near-phase collision. The default processing uses the contype and conaffinity masks, the parent-child filter and some other considerations related to welded bodies to decide if collision should be allowed. This callback replaces the default processing, but keep in mind that the entire mechanism is being replaced. So for example if you still want to take advantage of contype/conaffinity, you have to re-implement it in the callback.

    However, I am not sure how to implement this function to make this simple task of disabling some geom's collisions. If this is the function to achieve this task?

    Edit 2:

    I tried to implement it this way:

    Code:
    int customFiltering(const mjModel* m, mjData* d, int geom1, int geom2) {
        return 1;
    }
    
    extern mjfConFilt mjcb_confilter = customFiltering;
    To sanity check this behaviour.

    The expected behaviour is that collision checking is disabled for every object (i.e, a robot moving forward is penetrating with objects). Unfortunately, this is not the resulted behaviour, MuJoCo still create collisions (objects are reacting to forces)

    Moreover, it looks like the mjcb_confilter does not exist as a global pointer when importing mujoco.h. If I do this:

    Code:
    mjcb_confilter = customFiltering;
    The compile complains that mjcb_confilter is not defined.

    Edit 3:

    So it looks like there is a small typo in the documentation. It's not mjcb_confilter but mjcb_contactfilter, however, the mjcb_contactfilter is not of type mjfConFilt but of mjfGeneric.
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    You can change the geom contype and conaffinity parameters at runtime between simulation steps. For geom n, the fields in mjModel are:

    m->geom_contype[n]
    m->geom_conaffinity[n]

    Thanks for catching the typo in the documentation. Turns out there is another typo:
    mjcb_contactfilter is defined as type mjfConFilt when the software is compiled, but mujoco.h defines it as type mjfGeneric. So please make the change in your mujoco.h

    Note that the function should return 1 if the contact pair is to be discarded, and 0 if the contact pair is to be included.
     
  3. Thanks Emo.

    Actually, geom_contype and geom_conaffinity will disable all the collisions between that object, so for example if that object has a free joint and is supported on a table will fall down. So I need to implement my own mjcb_contactfilter to allow collision between a supporting surface and the object but with nothing else. I did manage to get this working with mjcb_contactfilter, however, I ran into a strange behaviour.

    I don't know how exactly the default filtering function is written but the one I am using here is:

    Code:
    int customFiltering(const mjModel* m, mjData* d, int geom1, int geom2) {
        int bodyInContact1 = m->body_rootid[m->geom_bodyid[geom1]];
        int bodyInContact2 = m->body_rootid[m->geom_bodyid[geom2]];
    
        // If any of the two bodies is the desired body to be ignored.
        if(bodyInContact1 == objectId || bodyInContact2 == objectId) {
            // And If any of the two bodies is the table.
            if(bodyInContact2 == tableId || bodyInContact1 == tableId) {
                // Then don't ignore collisions
                return false;
            }          
    
            // Ignore collisions
            return true;
        }
    
        // Don't ignore collisions, object not to be ignored
        return false;
    }
    
    Simulating 1 second results to:
    With custom filtering callback: 0.2978272 seconds.
    Without custom filtering callback: 0.1383046 seconds.

    This is just calling the step function without anything else.

    This makes the custom filtering callback slower than the default. My custom callback is of constant-time, why do I have this overhead? Is it because my program is in C++?

    Thank you in advance.
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    Hard to tell why it is slower. Maybe the C compiler managed to optimize things better, especially since all of MuJoCo is compiled as one module.

    You can use contype and conaffinity to create very elaborate collision rules, where a given geom is able to contact some geoms but not others. For example if you want enable A-B and B-C collisions but disable A-C collisions, you could set:

    contypeA = 1
    conaffinityA = 0


    contypeB = 1
    conaffinityB = 1

    contypeC = 1
    conaffinityC = 0

    Note that these are 32-bit bitmasks, you have lots of bits to play with.
     
    rafaelp likes this.