How to disable collisions?

Official Python bindings with a focus on reinforcement learning and robotics.
Post Reply
Senpid Sinclair
Posts: 2
Joined: Fri May 04, 2018 7:21 pm

How to disable collisions?

Post by Senpid Sinclair »

I know that collision detection/avoidance is what bullet is all about but I really just want to use it as a visualizer for robot stuff (like rviz but without ros) because it is very easy to setup.

So far for testing I am just loading robots via the URDF loader and they are going crazy when spawned into each other.

Now my question is: How can I either:
a) globally disable collisions or
b) disable collisions per object?

In another thread I found someone recommending setting a flag `CF_NO_CONTACT_RESPONSE` in the C++ code, but I haven't found that one in the pybullet lib and wouldn't know how to apply this. I was hoping that the URDF loader has this somehow as an optional flag, but not from what I saw.

Thanks so much in advance.
ardabbour
Posts: 9
Joined: Fri Oct 06, 2017 8:42 am

Re: How to disable collisions?

Post by ardabbour »

You can use visual shapes without collision shapes. For example, your URDF code can be:

Code: Select all

<?xml version="1.0"?>
<robot name="cube">
  <link name="base_link">

    <collision>
      <geometry>
        <box size="0 0 0"/>
      </geometry>
    </collision>

    <inertial>
      <mass value="0"/>
    	<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
  	</inertial>

    <visual>
      <geometry>
        <box size="1 1 1"/>
      </geometry>
    </visual>

  </link>
</robot>
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: How to disable collisions?

Post by Erwin Coumans »

I just implemented a few ways to do it:

Disable collisions per object pair / link:

Code: Select all

enableCollision= 0
pybullet.setCollisionFilterPair(objectUniqueIdA, objectUniqueIdB, linkIndexA, linkIndexB, enableCollision)
or disable collisions per group of objects:

Code: Select all

group = 0#other objects don't collide with me
mask=0 # don't collide with any other object
pybullet. setCollisionFilterGroupMask(objectUniqueId, linkIndex, group, mask)
Senpid Sinclair
Posts: 2
Joined: Fri May 04, 2018 7:21 pm

Re: How to disable collisions?

Post by Senpid Sinclair »

Thank you so much guys I will try it out immediately.
I am so glad this was answered after all.
abk
Posts: 1
Joined: Fri Oct 16, 2020 3:08 pm

Re: How to disable collisions?

Post by abk »

Hi Erwin,
If an object is fully masked (like you proposed), will it still have any affect on the physical simulation?
thanks
Post Reply