collision_detection#

class mplib.collision_detection.AllowedCollision#

Bases: pybind11_object

AllowedCollision Enum class

Members:

NEVER : Collision is never allowed

ALWAYS : Collision is always allowed

CONDITIONAL : Collision contact is allowed depending on a predicate

ALWAYS = <AllowedCollision.ALWAYS: 1>#
CONDITIONAL = <AllowedCollision.CONDITIONAL: 2>#
NEVER = <AllowedCollision.NEVER: 0>#
__init__(
self: mplib.pymp.collision_detection.AllowedCollision,
value: int,
) None#
property name#
property value#
class mplib.collision_detection.AllowedCollisionMatrix#

Bases: pybind11_object

AllowedCollisionMatrix for collision checking

All elements in the collision world are referred to by their names. This class represents which collisions are allowed to happen and which are not.

Mimicking MoveIt2’s collision_detection::AllowedCollisionMatrix

https://moveit.picknik.ai/main/api/html/classcollision__detection_1_1AllowedCollisionMatrix.html

__init__(
self: mplib.pymp.collision_detection.AllowedCollisionMatrix,
) None#
clear(
self: mplib.pymp.collision_detection.AllowedCollisionMatrix,
) None#

Clear all data in the allowed collision matrix

get_all_entry_names(
self: mplib.pymp.collision_detection.AllowedCollisionMatrix,
) list[str]#

Get sorted names of all existing elements (including default_entries_)

get_allowed_collision(
self: mplib.pymp.collision_detection.AllowedCollisionMatrix,
name1: str,
name2: str,
) mplib.pymp.collision_detection.AllowedCollision | None#

Get the type of the allowed collision between two elements

Returns:

AllowedCollision. This is * None if the entry does not exist (collision is not allowed) * the entry if an entry or a default entry exists.

get_default_entry(
self: mplib.pymp.collision_detection.AllowedCollisionMatrix,
name: str,
) mplib.pymp.collision_detection.AllowedCollision | None#

Get the default type of the allowed collision for an element

Parameters:

name – name of the element

Returns:

an AllowedCollision Enum or None if the default entry does not exist

get_entry(
self: mplib.pymp.collision_detection.AllowedCollisionMatrix,
name1: str,
name2: str,
) mplib.pymp.collision_detection.AllowedCollision | None#

Get the type of the allowed collision between two elements

Parameters:
  • name1 – name of the first element

  • name2 – name of the second element

Returns:

an AllowedCollision Enum or None if the entry does not exist.

has_default_entry(
self: mplib.pymp.collision_detection.AllowedCollisionMatrix,
name: str,
) bool#

Check if a default entry exists for an element

has_entry(*args, **kwargs)#

Overloaded function.

  1. has_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name: str) -> bool

Check if an entry exists for an element

  1. has_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name1: str, name2: str) -> bool

Check if an entry exists for a pair of elements

remove_default_entry(*args, **kwargs)#

Overloaded function.

  1. remove_default_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name: str) -> None

Remove the default entry for the element if exists

  1. remove_default_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, names: list[str]) -> None

Remove the existing default entries for the elements

remove_entry(*args, **kwargs)#

Overloaded function.

  1. remove_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name1: str, name2: str) -> None

Remove the entry for a pair of elements if exists

  1. remove_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name: str, other_names: list[str]) -> None

Remove existing entries between the element and each element in other_names

  1. remove_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, names1: list[str], names2: list[str]) -> None

Remove any existing entries for all possible pairs among two sets of elements

  1. remove_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name: str) -> None

Remove all entries for all possible pairs between the element and existing elements

  1. remove_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, names: list[str]) -> None

Remove all entries for all possible pairs between each of the elements and existing elements

set_default_entry(*args, **kwargs)#

Overloaded function.

  1. set_default_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name: str, allowed: bool) -> None

Set the default value for entries that include name but are not set explicitly with setEntry(). Apply to future changes of the element set.

  1. set_default_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, names: list[str], allowed: bool) -> None

Set the default entries for the elements. Apply to future changes of the element set.

set_entry(*args, **kwargs)#

Overloaded function.

  1. set_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name1: str, name2: str, allowed: bool) -> None

Set an entry for a pair of elements

  1. set_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name: str, other_names: list[str], allowed: bool) -> None

Set the entries between the element and each element in other_names

  1. set_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, names1: list[str], names2: list[str], allowed: bool) -> None

Set the entries for all possible pairs among two sets of elements

  1. set_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, name: str, allowed: bool) -> None

Set the entries for all possible pairs between the element and existing elements. As the set of elements might change in the future, consider using setDefaultEntry() instead.

  1. set_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, names: list[str], allowed: bool) -> None

Set the entries for all possible pairs between each of the elements and existing elements. As the set of elements might change in the future, consider using setDefaultEntry() instead.

  1. set_entry(self: mplib.pymp.collision_detection.AllowedCollisionMatrix, allowed: bool) -> None

Set the entries for all possible pairs among all existing elements

class mplib.collision_detection.WorldCollisionResult#

Bases: pybind11_object

Result of the collision checking.

__init__(*args, **kwargs)#

Overloaded function.

  1. __init__(self: mplib.pymp.collision_detection.WorldCollisionResult) -> None

Default constructor

  1. __init__(self: mplib.pymp.collision_detection.WorldCollisionResult, res: fcl::CollisionResult<double>, collision_type: str, object_name1: str, object_name2: str, link_name1: str, link_name2: str) -> None

Constructor with all members

property collision_type#

type of the collision

link name of the first object in collision

link name of the second object in collision

property object_name1#

name of the first object

property object_name2#

name of the second object

property res#

the fcl CollisionResult

class mplib.collision_detection.WorldDistanceResult#

Bases: pybind11_object

Result of minimum distance-to-collision query.

__init__(*args, **kwargs)#

Overloaded function.

  1. __init__(self: mplib.pymp.collision_detection.WorldDistanceResult) -> None

Default constructor

  1. __init__(self: mplib.pymp.collision_detection.WorldDistanceResult, res: fcl::DistanceResult<double>, min_distance: float, distance_type: str, object_name1: str, object_name2: str, link_name1: str, link_name2: str) -> None

Constructor with all members

property distance_type#

type of the distance result

link name of the first object

link name of the second object

property min_distance#

minimum distance between the two objects

property object_name1#

name of the first object

property object_name2#

name of the second object

property res#

the fcl DistanceResult