Avoid self collisions constraint#

Once your collisions are setup, the AvoidSelfCollisionsConstraint can be used to prevent self collisions between the robot links.

Internally, it uses the distances computation to compute the distances and closest points between possible collision pairs. An inequality is then added during the solve step to prevent the closest points to be closer than a given margin.

Warning

While this feature might be useful for some applications, you should be aware of the following points:

  • This constraint can add significant computation time if you have many links that can collide. Be sure your collision model is clean, prefferably with pure shapes and avoiding complex shapes.

  • Be sure your shapes don’t overlap. Otherwise, please specify your collision pairs in the collision model.

  • The kinematics solver only solves for one small timestep ahead. For this reason, self collisions avoidance could lead a trajectory to a local optimum where the robot is stuck. Getting out of such situation is a planning problem which is out of the scope of such solver.

Creating the constraint#

The constraint can be created by calling add_avoid_self_collisions_constraint() on the solver:

# Adds the constraint to the solver
collisions_constraint = solver.add_avoid_self_collisions_constraint()

Configuring the constraint#

You can configure the following parameters on the constraint:

# Margin to avoid self collisions
collisions_constraint.self_collisions_margin = 0.01 # 1cm

# Distance where the constraint starts being active in the solver
# (to avoid extra computations for parts that are far away)
collisions_constraint.self_collisions_trigger = 0.05 # 5cm

Example#

Humanoid robot with self collisions avoidance

Example code: kinematics/humanoid_collisions.py