Disable collisions for specific bodies at run-time

Discussion in 'Simulation' started by rafaelp, Jun 27, 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, can somebody provide some guidance on how to implement it?

    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.
     
    Last edited: Jun 27, 2019
  2. 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.

    I am really confused. Is this the best way to achieve what I am looking for?