fcl#

FCL submodule

class mplib.pymp.collision_detection.fcl.BVHModel#

Bases: CollisionGeometry

BVHModel collision geometry.

Inheriting from CollisionGeometry, this class specializes to a mesh geometry represented by a BVH tree.

addSubModel(*args, **kwargs)#

Overloaded function.

  1. addSubModel(self: mplib.pymp.collision_detection.fcl.BVHModel, vertices: list[numpy.ndarray[numpy.float64[3, 1]]]) -> int

Add a sub-model to the BVHModel.

Parameters:

vertices – vertices of the sub-model

  1. addSubModel(self: mplib.pymp.collision_detection.fcl.BVHModel, vertices: list[numpy.ndarray[numpy.float64[3, 1]]], faces: list[mplib.pymp.collision_detection.fcl.Triangle]) -> int

Add a sub-model to the BVHModel.

Parameters:
  • vertices – vertices of the sub-model

  • faces – faces of the sub-model represented by a list of vertex indices

  1. addSubModel(self: mplib.pymp.collision_detection.fcl.BVHModel, vertices: list[numpy.ndarray[numpy.float64[3, 1]]], faces: list[numpy.ndarray[numpy.int32[3, 1]]]) -> None

Add a sub-model to the BVHModel.

Parameters:
  • vertices – vertices of the sub-model

  • faces – faces of the sub-model represented by a list of vertex indices

beginModel(self: mplib.pymp.collision_detection.fcl.BVHModel, num_faces: int = 0, num_vertices: int = 0) int#

Begin to construct a BVHModel.

Parameters:
  • num_faces – number of faces of the mesh

  • num_vertices – number of vertices of the mesh

endModel(self: mplib.pymp.collision_detection.fcl.BVHModel) int#

End the construction of a BVHModel.

get_faces(self: mplib.pymp.collision_detection.fcl.BVHModel) list[mplib.pymp.collision_detection.fcl.Triangle]#

Get the faces of the BVHModel.

Returns:

faces of the BVHModel

get_vertices(self: mplib.pymp.collision_detection.fcl.BVHModel) list[numpy.ndarray[numpy.float64[3, 1]]]#

Get the vertices of the BVHModel.

Returns:

vertices of the BVHModel

property num_faces#
property num_vertices#
class mplib.pymp.collision_detection.fcl.Box#

Bases: CollisionGeometry

Box collision geometry.

Inheriting from CollisionGeometry, this class specializes to a box geometry.

property side#
class mplib.pymp.collision_detection.fcl.Capsule#

Bases: CollisionGeometry

Capsule collision geometry.

Inheriting from CollisionGeometry, this class specializes to a capsule geometry.

property lz#
property radius#
class mplib.pymp.collision_detection.fcl.CollisionGeometry#

Bases: pybind11_object

Collision geometry base class.

This is an FCL class so you can refer to the FCL doc here. https://flexible-collision-library.github.io/d6/d5d/classfcl_1_1CollisionGeometry.html

property aabb_center#
property aabb_radius#
computeCOM(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) numpy.ndarray[numpy.float64[3, 1]]#
computeLocalAABB(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) None#
computeMomentofInertia(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) numpy.ndarray[numpy.float64[3, 3]]#
computeMomentofInertiaRelatedToCOM(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) numpy.ndarray[numpy.float64[3, 3]]#
computeVolume(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) float#
property cost_density#
isFree(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) bool#
isOccupied(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) bool#
isUncertain(self: mplib.pymp.collision_detection.fcl.CollisionGeometry) bool#
class mplib.pymp.collision_detection.fcl.CollisionObject#

Bases: pybind11_object

Collision object class.

This class contains the collision geometry and the transformation of the geometry.

get_collision_geometry(self: mplib.pymp.collision_detection.fcl.CollisionObject) mplib.pymp.collision_detection.fcl.CollisionGeometry#
get_rotation(self: mplib.pymp.collision_detection.fcl.CollisionObject) numpy.ndarray[numpy.float64[3, 3]]#
get_translation(self: mplib.pymp.collision_detection.fcl.CollisionObject) numpy.ndarray[numpy.float64[3, 1]]#
set_transformation(self: mplib.pymp.collision_detection.fcl.CollisionObject, arg0: numpy.ndarray[numpy.float64[7, 1]]) None#
class mplib.pymp.collision_detection.fcl.CollisionRequest#

Bases: pybind11_object

isSatisfied(self: mplib.pymp.collision_detection.fcl.CollisionRequest, result: fcl::CollisionResult<double>) bool#
class mplib.pymp.collision_detection.fcl.CollisionResult#

Bases: pybind11_object

add_contact(self: mplib.pymp.collision_detection.fcl.CollisionResult, c: fcl::Contact<double>) None#
add_cost_source(self: mplib.pymp.collision_detection.fcl.CollisionResult, c: fcl::CostSource<double>, num_max_cost_sources: int) None#
clear(self: mplib.pymp.collision_detection.fcl.CollisionResult) None#
get_contact(self: mplib.pymp.collision_detection.fcl.CollisionResult, i: int) fcl::Contact<double>#
get_contacts(self: mplib.pymp.collision_detection.fcl.CollisionResult) list[fcl::Contact<double>]#
get_cost_sources(self: mplib.pymp.collision_detection.fcl.CollisionResult) list[fcl::CostSource<double>]#
is_collision(self: mplib.pymp.collision_detection.fcl.CollisionResult) bool#
num_contacts(self: mplib.pymp.collision_detection.fcl.CollisionResult) int#
num_cost_sources(self: mplib.pymp.collision_detection.fcl.CollisionResult) int#
class mplib.pymp.collision_detection.fcl.Cone#

Bases: CollisionGeometry

Cone collision geometry.

Inheriting from CollisionGeometry, this class specializes to a cone geometry.

property lz#
property radius#
class mplib.pymp.collision_detection.fcl.Contact#

Bases: pybind11_object

property normal#
property penetration_depth#
property pos#
class mplib.pymp.collision_detection.fcl.ContactPoint#

Bases: pybind11_object

property normal#
property penetration_depth#
property pos#
class mplib.pymp.collision_detection.fcl.Convex#

Bases: CollisionGeometry

Convex collision geometry.

Inheriting from CollisionGeometry, this class specializes to a convex geometry.

compute_volume(self: mplib.pymp.collision_detection.fcl.Convex) float#

Compute the volume of the convex.

Returns:

volume of the convex

get_face_count(self: mplib.pymp.collision_detection.fcl.Convex) int#

Get the number of faces of the convex.

Returns:

number of faces of the convex

get_faces(self: mplib.pymp.collision_detection.fcl.Convex) list[int]#

Get the faces of the convex.

Returns:

faces of the convex represented by a list of vertex indices

get_interior_point(self: mplib.pymp.collision_detection.fcl.Convex) numpy.ndarray[numpy.float64[3, 1]]#

Sample a random interior point of the convex geometry

Returns:

interior point of the convex

get_vertices(self: mplib.pymp.collision_detection.fcl.Convex) list[numpy.ndarray[numpy.float64[3, 1]]]#

Get the vertices of the convex.

Returns:

vertices of the convex

class mplib.pymp.collision_detection.fcl.CostSource#

Bases: pybind11_object

property aabb_max#
property aabb_min#
property cost_density#
property total_cost#
class mplib.pymp.collision_detection.fcl.Cylinder#

Bases: CollisionGeometry

Cylinder collision geometry.

Inheriting from CollisionGeometry, this class specializes to a cylinder geometry.

property lz#
property radius#
class mplib.pymp.collision_detection.fcl.DistanceRequest#

Bases: pybind11_object

isSatisfied(self: mplib.pymp.collision_detection.fcl.DistanceRequest, result: fcl::DistanceResult<double>) bool#
class mplib.pymp.collision_detection.fcl.DistanceResult#

Bases: pybind11_object

clear(self: mplib.pymp.collision_detection.fcl.DistanceResult) None#
property min_distance#
property nearest_points#
class mplib.pymp.collision_detection.fcl.FCLModel#

Bases: pybind11_object

FCL collision model of an articulation

See https://github.com/flexible-collision-library/fcl

collide(self: mplib.pymp.collision_detection.fcl.FCLModel, request: mplib.pymp.collision_detection.fcl.CollisionRequest = <mplib.pymp.collision_detection.fcl.CollisionRequest object at 0x7fee815e1fb0>) bool#

Perform self-collision checking.

Parameters:

request – collision request

Returns:

True if any collision pair collides

collide_full(self: mplib.pymp.collision_detection.fcl.FCLModel, request: mplib.pymp.collision_detection.fcl.CollisionRequest = <mplib.pymp.collision_detection.fcl.CollisionRequest object at 0x7fee815e20f0>) list[mplib.pymp.collision_detection.fcl.CollisionResult]#

Perform self-collision checking and returns all found collisions.

Parameters:

request – collision request

Returns:

list of CollisionResult for each collision pair

get_collision_objects(self: mplib.pymp.collision_detection.fcl.FCLModel) list[mplib.pymp.collision_detection.fcl.CollisionObject]#

Get the collision objects of the FCL model.

Returns:

all collision objects of the FCL model

get_collision_pairs(self: mplib.pymp.collision_detection.fcl.FCLModel) list[tuple[int, int]]#

Get the collision pairs of the FCL model.

Returns:

collision pairs of the FCL model. If the FCL model has N collision objects, the collision pairs is a list of N*(N-1)/2 pairs minus the disabled collision pairs

remove_collision_pairs_from_srdf(self: mplib.pymp.collision_detection.fcl.FCLModel, srdf_filename: str) None#

Remove collision pairs from SRDF.

Parameters:

srdf_filename – path to SRDF file, can be relative to the current working directory

Set the link order of the FCL model.

Parameters:

names – list of link names in the order that you want to set.

update_collision_objects(self: mplib.pymp.collision_detection.fcl.FCLModel, link_poses: list[numpy.ndarray[numpy.float64[7, 1]]]) None#

Update the collision objects of the FCL model.

Parameters:

link_poses – list of link poses in the order of the link order

class mplib.pymp.collision_detection.fcl.GJKSolverType#

Bases: pybind11_object

Members:

GST_LIBCCD

GST_INDEP

GST_INDEP = <GJKSolverType.GST_INDEP: 1>#
GST_LIBCCD = <GJKSolverType.GST_LIBCCD: 0>#
property name#
property value#
class mplib.pymp.collision_detection.fcl.OcTree#

Bases: CollisionGeometry

OcTree collision geometry.

Inheriting from CollisionGeometry, this class specializes to a point cloud geometry represented by an OcTree.

class mplib.pymp.collision_detection.fcl.Plane#

Bases: CollisionGeometry

Infinite plane collision geometry.

Inheriting from CollisionGeometry, this class specializes to a plane geometry.

property d#
property n#
class mplib.pymp.collision_detection.fcl.Sphere#

Bases: CollisionGeometry

Sphere collision geometry.

Inheriting from CollisionGeometry, this class specializes to a sphere geometry.

property radius#
class mplib.pymp.collision_detection.fcl.Triangle#

Bases: pybind11_object

Triangle with 3 indices for points.

This is an FCL class so you can refer to the FCL doc here. https://flexible-collision-library.github.io/de/daa/classfcl_1_1Triangle.html

get(self: mplib.pymp.collision_detection.fcl.Triangle, arg0: int) int#
set(self: mplib.pymp.collision_detection.fcl.Triangle, arg0: int, arg1: int, arg2: int) None#
mplib.pymp.collision_detection.fcl.collide(arg0: mplib.pymp.collision_detection.fcl.CollisionObject, arg1: mplib.pymp.collision_detection.fcl.CollisionObject, arg2: mplib.pymp.collision_detection.fcl.CollisionRequest) mplib.pymp.collision_detection.fcl.CollisionResult#
mplib.pymp.collision_detection.fcl.distance(arg0: mplib.pymp.collision_detection.fcl.CollisionObject, arg1: mplib.pymp.collision_detection.fcl.CollisionObject, arg2: mplib.pymp.collision_detection.fcl.DistanceRequest) mplib.pymp.collision_detection.fcl.DistanceResult#
mplib.pymp.collision_detection.fcl.load_mesh_as_BVH(mesh_path: str, scale: numpy.ndarray[numpy.float64[3, 1]]) mplib.pymp.collision_detection.fcl.BVHModel#
mplib.pymp.collision_detection.fcl.load_mesh_as_Convex(mesh_path: str, scale: numpy.ndarray[numpy.float64[3, 1]]) mplib.pymp.collision_detection.fcl.Convex#