Skip to main content

Python bindings for the Flexible Collision Library

Project description

python-fcl

Python Interface for the Flexible Collision Library

Python-FCL is an (unofficial) Python interface for the Flexible Collision Library (FCL), an excellent C++ library for performing proximity and collision queries on pairs of geometric models. Currently, this package is targeted for FCL 0.7.0.

This package supports three types of proximity queries for pairs of geometric models:

  • Collision Detection: Detecting whether two models overlap (and optionally where).
  • Distance Computation: Computing the minimum distance between a pair of models.
  • Continuous Collision Detection: Detecting whether two models overlap during motion (and optionally the time of contact).

This package also supports most of FCL's object shapes, including:

  • TriangleP
  • Box
  • Sphere
  • Ellipsoid
  • Capsule
  • Cone
  • Convex
  • Cylinder
  • Half-Space
  • Plane
  • Mesh
  • OcTree

Installation

First, install octomap, which is necessary to use OcTree. For Ubuntu, use sudo apt-get install liboctomap-dev. Second, install FCL using the instructions provided here. If you're on Ubuntu 17.04 or newer, you can install FCL using sudo apt-get install libfcl-dev. Otherwise, just compile FCL from source -- it's quick and easy, and its dependencies are all easily installed via apt or brew. Note: the provided install scripts (under build_dependencies) can automate this process as well.

In order to install the Python wrappers for FCL, simply run

pip install python-fcl

Objects

Collision Objects

The primary construct in FCL is the CollisionObject, which forms the backbone of all collision and distance computations. A CollisionObject consists of two components -- its geometry, defined by a CollisionGeometry object, and its pose, defined by a Transform object.

Collision Geometries

There are two main types of CollisionGeometry objects -- geometric primitives, such as boxes and spheres, and arbitrary triangular meshes. Here's some examples of how to instantiate geometric primitives. Note that the box, sphere, ellipsoid, capsule, cone, and cylinder are all centered at the origin.

import numpy as np
import fcl

v1 = np.array([1.0, 2.0, 3.0])
v2 = np.array([2.0, 1.0, 3.0])
v3 = np.array([3.0, 2.0, 1.0])
x, y, z = 1, 2, 3
rad, lz = 1.0, 3.0
n = np.array([1.0, 0.0, 0.0])
d = 5.0

t = fcl.TriangleP(v1, v2, v3) # Triangle defined by three points
b = fcl.Box(x, y, z)          # Axis-aligned box with given side lengths
s = fcl.Sphere(rad)           # Sphere with given radius
e = fcl.Ellipsoid(x, y, z)    # Axis-aligned ellipsoid with given radii
c = fcl.Capsule(rad, lz)      # Capsule with given radius and height along z-axis
c = fcl.Cone(rad, lz)         # Cone with given radius and cylinder height along z-axis
c = fcl.Cylinder(rad, lz)     # Cylinder with given radius and height along z-axis
h = fcl.Halfspace(n, d)       # Half-space defined by {x : <n, x> < d}
p = fcl.Plane(n, d)           # Plane defined by {x : <n, x> = d}

Triangular meshes are wrapped by the BVHModel class, and they are instantiated a bit differently.

verts = np.array([[1.0, 1.0, 1.0],
                  [2.0, 1.0, 1.0],
                  [1.0, 2.0, 1.0],
                  [1.0, 1.0, 2.0]])
tris  = np.array([[0,2,1],
                  [0,3,2],
                  [0,1,3],
                  [1,2,3]])

m = fcl.BVHModel()
m.beginModel(len(verts), len(tris))
m.addSubModel(verts, tris)
m.endModel()

If the mesh is convex, such as the example above, you can also wrap it in the Convex class. Note that the instantiation is a bit different because the Convex class supports arbitrary polygons for each face of the convex object.

verts = np.array([[1.0, 1.0, 1.0],
                  [2.0, 1.0, 1.0],
                  [1.0, 2.0, 1.0],
                  [1.0, 1.0, 2.0]])
tris  = np.array([[0,2,1],
                  [0,3,2],
                  [0,1,3],
                  [1,2,3]])
faces = np.concatenate((3 * np.ones((len(tris), 1), dtype=np.int64), tris), axis=1).flatten()
c = fcl.Convex(verts, len(tris), faces)

Transforms

In addition to a CollisionGeometry, a CollisionObject requires a Transform, which tells FCL where the CollisionGeometry is actually located in the world. All Transform objects specify a rigid transformation (i.e. a rotation and a translation). The translation is always a 3-entry vector, while the rotation can be specified by a 3x3 rotation matrix or a 4-entry quaternion.

Here are some examples of possible ways to instantiate and manipulate a Transform.

R = np.array([[0.0, -1.0, 0.0],
              [1.0,  0.0, 0.0],
              [0.0,  0.0, 1.0]])
T = np.array([1.0, 2.0, 3.0])
q = np.array([0.707, 0.0, 0.0, 0.707])

tf = fcl.Transform()     # Default gives identity transform
tf = fcl.Transform(q)    # Quaternion rotation, zero translation
tf = fcl.Transform(R)    # Matrix rotation, zero translation
tf = fcl.Transform(T)    # Translation, identity rotation
tf = fcl.Transform(q, T) # Quaternion rotation and translation
tf = fcl.Transform(R, T) # Matrix rotation and translation
tf1 = fcl.Transform(tf)  # Can also initialize with another Transform

Now, given a CollisionGeometry and a Transform, we can create a CollisionObject:

t = fcl.Transform(R, T)
b = fcl.Box(x, y, z)
obj = fcl.CollisionObject(b, t)

The transform of a collision object can be modified in-place:

t1 = fcl.Transform(R1, T1)
obj.setTransform(t1)   # Using a transform
obj.setRotation(R2)    # Specifying components individually
obj.setTranslation(T2)
obj.setQuatRotation(q2)

Commands

Pairwise Operations

Given a pair of collision objects, this library supports three types of queries:

  • Collision Detection
  • Distance Computation
  • Continuous Collision Detection

The interfaces for each of these operations follow a common pipeline. First, a query request data structure is initialized and populated with parameters. Then, an empty query response structure is initialized. Finally, the query function is called with the two CollisionObject items, the request structure, and the response structure as arguments. The query function returns a scalar result, and any additional information is stored in the query result data structure. Examples of all three operations are shown below.

Collision Checking

g1 = fcl.Box(1,2,3)
t1 = fcl.Transform()
o1 = fcl.CollisionObject(g1, t1)

g2 = fcl.Cone(1,3)
t2 = fcl.Transform()
o2 = fcl.CollisionObject(g2, t2)

request = fcl.CollisionRequest()
result = fcl.CollisionResult()

ret = fcl.collide(o1, o2, request, result)

After calling fcl.collide(), ret contains the number of contacts generated between the two objects, and result contains information about the collision and contacts. For more information about available parameters for collision requests and results, see fcl/collision_data.py.

Distance Checking

g1 = fcl.Box(1,2,3)
t1 = fcl.Transform()
o1 = fcl.CollisionObject(g1, t1)

g2 = fcl.Cone(1,3)
t2 = fcl.Transform()
o2 = fcl.CollisionObject(g2, t2)

request = fcl.DistanceRequest()
result = fcl.DistanceResult()

ret = fcl.distance(o1, o2, request, result)

After calling fcl.distance(), ret contains the minimum distance between the two objects and result contains information about the closest points on the objects. If ret is negative, the objects are in collision. For more information about available parameters for distance requests and results, see fcl/collision_data.py.

Continuous Collision Checking

g1 = fcl.Box(1,2,3)
t1 = fcl.Transform()
o1 = fcl.CollisionObject(g1, t1)
t1_final = fcl.Transform(np.array([1.0, 0.0, 0.0]))

g2 = fcl.Cone(1,3)
t2 = fcl.Transform()
o2 = fcl.CollisionObject(g2, t2)
t2_final = fcl.Transform(np.array([-1.0, 0.0, 0.0]))

request = fcl.ContinuousCollisionRequest()
result = fcl.ContinuousCollisionResult()

ret = fcl.continuousCollide(o1, t1_final, o2, t2_final, request, result)

After calling fcl.continuousCollide(), ret contains the time of contact in (0,1), or 1.0 if the objects did not collide during movement from their initial poses to their final poses. Additionally, result contains information about the collision time and status. For more information about available parameters for continuous collision requests and results, see fcl/collision_data.py.

Broadphase Checking

In addition to pairwise checks, FCL supports broadphase collision/distance queries between groups of objects and can avoid n-squared complexity. Specifically, CollisionObject items are registered with a DynamicAABBTreeCollisionManager before collision or distance checking is performed.

Three types of checks are possible:

  • One-to-many: Collision/distance checking between a stand-alone CollisionObject and all objects managed by a manager.
  • Internal many-to-many: Pairwise collision/distance checking between all pairs of objects managed by a manager.
  • Group many-to-many: Pairwise collision/distance checking between items from two managers.

In general, the collision methods can return all contact pairs, while the distance methods will just return the single closest distance between any pair of objects. Here are some examples of managed collision checking. The methods take a callback function -- use the defaults from python-fcl unless you have a special use case -- and a wrapper object, either CollisionData or DistanceData, that wraps a request-response pair. This object also has a field, done, that tells the recursive collision checker when to quit. Be sure to use a new Data object for each request or set the done attribute to False before reusing one.

objs1 = [fcl.CollisionObject(box), fcl.CollisionObject(sphere)]
objs2 = [fcl.CollisionObject(cone), fcl.CollisionObject(mesh)]

manager1 = fcl.DynamicAABBTreeCollisionManager()
manager2 = fcl.DynamicAABBTreeCollisionManager()

manager1.registerObjects(objs1)
manager2.registerObjects(objs2)

manager1.setup()
manager2.setup()

#=====================================================================
# Managed internal (sub-n^2) collision checking
#=====================================================================
cdata = fcl.CollisionData()
manager1.collide(cdata, fcl.defaultCollisionCallback)
print 'Collision within manager 1?: {}'.format(cdata.result.is_collision)

##=====================================================================
## Managed internal (sub-n^2) distance checking
##=====================================================================
ddata = fcl.DistanceData()
manager1.distance(ddata, fcl.defaultDistanceCallback)
print 'Closest distance within manager 1?: {}'.format(ddata.result.min_distance)

#=====================================================================
# Managed one to many collision checking
#=====================================================================
req = fcl.CollisionRequest(num_max_contacts=100, enable_contact=True)
rdata = fcl.CollisionData(request = req)

manager1.collide(fcl.CollisionObject(mesh), rdata, fcl.defaultCollisionCallback)
print 'Collision between manager 1 and Mesh?: {}'.format(rdata.result.is_collision)
print 'Contacts:'
for c in rdata.result.contacts:
    print '\tO1: {}, O2: {}'.format(c.o1, c.o2)

#=====================================================================
# Managed many to many collision checking
#=====================================================================
rdata = fcl.CollisionData(request = req)
manager1.collide(manager2, rdata, fcl.defaultCollisionCallback)
print 'Collision between manager 1 and manager 2?: {}'.format(rdata.result.is_collision)
print 'Contacts:'
for c in rdata.result.contacts:
    print '\tO1: {}, O2: {}'.format(c.o1, c.o2)

Extracting Which Objects Are In Collision

To determine which objects are actually in collision, you'll need parse the collision data's contacts and use an additional external data structure.

Specifically, the fcl.CollisionData object that is passed into any collide() call has an internal set of contacts, stored in cdata.result.contacts. This object is a simple list of Contact objects, each of which represents a contact point between two objects. Each contact object has two attributes, o1 and o2, that store references to the original fcl.CollisionGeometry objects were created for the two fcl.CollisionObject objects that are in collision. This is a bit wonky, but it's part of the FCL API.

Therefore, all you have to do is make a map from the id of each fcl.CollisionGeometry object to either the actual fcl.CollisionObject it corresponds to or to some string identifier for each object. Then, you can iterate over cdata.result.contacts, extract o1 and o2, apply the built-in id() function to each, and find the corresponding data you want in your map.

Here's an example.

import fcl
import numpy as np

# Create collision geometry and objects
geom1 = fcl.Cylinder(1.0, 1.0)
obj1 = fcl.CollisionObject(geom1)

geom2 = fcl.Cylinder(1.0, 1.0)
obj2 = fcl.CollisionObject(geom2, fcl.Transform(np.array([0.0, 0.0, 0.3])))

geom3 = fcl.Cylinder(1.0, 1.0)
obj3 = fcl.CollisionObject(geom3, fcl.Transform(np.array([0.0, 0.0, 3.0])))

geoms = [geom1, geom2, geom3]
objs = [obj1, obj2, obj3]
names = ['obj1', 'obj2', 'obj3']

# Create map from geometry IDs to objects
geom_id_to_obj = { id(geom) : obj for geom, obj in zip(geoms, objs) }

# Create map from geometry IDs to string names
geom_id_to_name = { id(geom) : name for geom, name in zip(geoms, names) }

# Create manager
manager = fcl.DynamicAABBTreeCollisionManager()
manager.registerObjects(objs)
manager.setup()

# Create collision request structure
crequest = fcl.CollisionRequest(num_max_contacts=100, enable_contact=True)
cdata = fcl.CollisionData(crequest, fcl.CollisionResult())

# Run collision request
manager.collide(cdata, fcl.defaultCollisionCallback)

# Extract collision data from contacts and use that to infer set of
# objects that are in collision
objs_in_collision = set()

for contact in cdata.result.contacts:
    # Extract collision geometries that are in contact
    coll_geom_0 = contact.o1
    coll_geom_1 = contact.o2

    # Get their names
    coll_names = [geom_id_to_name[id(coll_geom_0)], geom_id_to_name[id(coll_geom_1)]]
    coll_names = tuple(sorted(coll_names))
    objs_in_collision.add(coll_names)

for coll_pair in objs_in_collision:
    print('Object {} in collision with object {}!'.format(coll_pair[0], coll_pair[1]))
>>> Object obj1 in collision with object obj2!

For more examples, see examples/example.py.

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distributions

No source distribution files available for this release.See tutorial on generating distribution archives.

Built Distributions

fclx-0.7.0.8-cp313-cp313-win_amd64.whl (1.1 MB view details)

Uploaded CPython 3.13 Windows x86-64

fclx-0.7.0.8-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (4.6 MB view details)

Uploaded CPython 3.13 manylinux: glibc 2.17+ x86-64

fclx-0.7.0.8-cp313-cp313-macosx_11_0_arm64.whl (1.7 MB view details)

Uploaded CPython 3.13 macOS 11.0+ ARM64

fclx-0.7.0.8-cp313-cp313-macosx_10_13_x86_64.whl (2.0 MB view details)

Uploaded CPython 3.13 macOS 10.13+ x86-64

fclx-0.7.0.8-cp312-cp312-win_amd64.whl (1.1 MB view details)

Uploaded CPython 3.12 Windows x86-64

fclx-0.7.0.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (4.6 MB view details)

Uploaded CPython 3.12 manylinux: glibc 2.17+ x86-64

fclx-0.7.0.8-cp312-cp312-macosx_11_0_arm64.whl (1.7 MB view details)

Uploaded CPython 3.12 macOS 11.0+ ARM64

fclx-0.7.0.8-cp312-cp312-macosx_10_13_x86_64.whl (2.0 MB view details)

Uploaded CPython 3.12 macOS 10.13+ x86-64

fclx-0.7.0.8-cp311-cp311-win_amd64.whl (1.1 MB view details)

Uploaded CPython 3.11 Windows x86-64

fclx-0.7.0.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (4.6 MB view details)

Uploaded CPython 3.11 manylinux: glibc 2.17+ x86-64

fclx-0.7.0.8-cp311-cp311-macosx_11_0_arm64.whl (1.7 MB view details)

Uploaded CPython 3.11 macOS 11.0+ ARM64

fclx-0.7.0.8-cp311-cp311-macosx_10_9_x86_64.whl (2.0 MB view details)

Uploaded CPython 3.11 macOS 10.9+ x86-64

fclx-0.7.0.8-cp310-cp310-win_amd64.whl (1.1 MB view details)

Uploaded CPython 3.10 Windows x86-64

fclx-0.7.0.8-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (4.5 MB view details)

Uploaded CPython 3.10 manylinux: glibc 2.17+ x86-64

fclx-0.7.0.8-cp310-cp310-macosx_11_0_arm64.whl (1.7 MB view details)

Uploaded CPython 3.10 macOS 11.0+ ARM64

fclx-0.7.0.8-cp310-cp310-macosx_10_9_x86_64.whl (2.0 MB view details)

Uploaded CPython 3.10 macOS 10.9+ x86-64

fclx-0.7.0.8-cp39-cp39-win_amd64.whl (1.1 MB view details)

Uploaded CPython 3.9 Windows x86-64

fclx-0.7.0.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (4.6 MB view details)

Uploaded CPython 3.9 manylinux: glibc 2.17+ x86-64

fclx-0.7.0.8-cp39-cp39-macosx_11_0_arm64.whl (1.7 MB view details)

Uploaded CPython 3.9 macOS 11.0+ ARM64

fclx-0.7.0.8-cp39-cp39-macosx_10_9_x86_64.whl (2.0 MB view details)

Uploaded CPython 3.9 macOS 10.9+ x86-64

File details

Details for the file fclx-0.7.0.8-cp313-cp313-win_amd64.whl.

File metadata

  • Download URL: fclx-0.7.0.8-cp313-cp313-win_amd64.whl
  • Upload date:
  • Size: 1.1 MB
  • Tags: CPython 3.13, Windows x86-64
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/4.0.2 CPython/3.11.11

File hashes

Hashes for fclx-0.7.0.8-cp313-cp313-win_amd64.whl
Algorithm Hash digest
SHA256 20c117044cc42f667889e10a098a58e1affec8338a405863ea7e57beff54ecd1
MD5 bcdbd76155aff4d470f3bd8ec481d521
BLAKE2b-256 085c7e5fbc8a92c32d3b8e4452c1b9e503fe9d1640f51aebffb4fd4b7f32bb7e

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 8723768a56da074ce66f4bdccd955bdbfbac2db3e68979620b694ccbfe49d84d
MD5 a5d46589f0663af97276c35c1ddcc360
BLAKE2b-256 013f24e616d480841e5192edb83269799c652d4c952f31cfa2c4d33006608f4d

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp313-cp313-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp313-cp313-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 85be2067a8c8bd980065bc18966e1337d28ab52a6e96a1c352d7f28d99304dcd
MD5 7d7374130eb9d8a21032e62c9f80f92e
BLAKE2b-256 50c2d3fe5ae0d49d421219fe56cce62a82fb483d829ed353bf23c143ab20eee1

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp313-cp313-macosx_10_13_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp313-cp313-macosx_10_13_x86_64.whl
Algorithm Hash digest
SHA256 e718f4db631852b4695d1e80f78bbd411c9052ce56e2876eafe41ddb5c6d184e
MD5 e98f523770e2270487e14223a51133f7
BLAKE2b-256 6c858bebffb76ee136270ac5e63a03a40136df9002b400872e83e82a77b438e6

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp312-cp312-win_amd64.whl.

File metadata

  • Download URL: fclx-0.7.0.8-cp312-cp312-win_amd64.whl
  • Upload date:
  • Size: 1.1 MB
  • Tags: CPython 3.12, Windows x86-64
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/4.0.2 CPython/3.11.11

File hashes

Hashes for fclx-0.7.0.8-cp312-cp312-win_amd64.whl
Algorithm Hash digest
SHA256 fc764914bc4ba950c552c0690cce11e723c70fe86ea1e60b40251b5d16e769e8
MD5 fe3d059f0fc8ad24d6eacb47482fba38
BLAKE2b-256 efa081c25940ce20fa569b9748c56a2e4d2c21b92beffc61028f8b219a6655b6

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 f5a6147819cb95370bcee4e8b5c3de3564fd20bf35c7df577b31eac8c00f9b38
MD5 c80cb437838a30aa5a94f7c71b39adb3
BLAKE2b-256 0d3fd4dbf83d2685d4a17dec4791576da867e1ce8a52c1130acd48a5ca5af453

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp312-cp312-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp312-cp312-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 053852d87a45deb6c10c76e580a2a4bfac4fde4fadf94ce301f05550e6b31d72
MD5 474a2577309bc23f09d480dd1842902c
BLAKE2b-256 e5c0bf9baf64c7c11f4494ad121e1cba42303549c59a8ba25cdeb4e4c048abf4

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp312-cp312-macosx_10_13_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp312-cp312-macosx_10_13_x86_64.whl
Algorithm Hash digest
SHA256 f348badaa9a15994fbfe76c4897dbbd653921de473b7ed9cf082e69e1af353a4
MD5 fb4b48e850e51812d1b595b7f9ed7dae
BLAKE2b-256 5e458ea19550381281d8bb3a6c3164505bb88e41ec47ce4036d4cc6e582024fb

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp311-cp311-win_amd64.whl.

File metadata

  • Download URL: fclx-0.7.0.8-cp311-cp311-win_amd64.whl
  • Upload date:
  • Size: 1.1 MB
  • Tags: CPython 3.11, Windows x86-64
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/4.0.2 CPython/3.11.11

File hashes

Hashes for fclx-0.7.0.8-cp311-cp311-win_amd64.whl
Algorithm Hash digest
SHA256 a4c2a5595c13b15a5c093428780a1086ef59c502d2501b8451ff84c22ae285ad
MD5 77243d32e49a7de846baaedcc3ae8196
BLAKE2b-256 f4991b6f3d732df540952511c322503b1135105cb6bc33602daeedb8721e343f

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 61667340f8cdc9ea791c9b32aeb2380b55f72c87d6677fda8c1133037320c8d1
MD5 33c1eea4fcb556ff5541f12a451e082e
BLAKE2b-256 d5874c98c0372cb3a831cc921f7318ab3746d6d3a7f15fcdea3d978c758242a8

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp311-cp311-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp311-cp311-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 2b86352641b6266ac795eb19fb5312378d37edeaceeabf32795c24176eab876b
MD5 43c554d2aa838451d98b83f1047348ce
BLAKE2b-256 e5e144faa01bfaaed5ddbb8d3248a84691e8f169c16809f7592901d915ee9e87

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp311-cp311-macosx_10_9_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp311-cp311-macosx_10_9_x86_64.whl
Algorithm Hash digest
SHA256 18dfcc1408688d3486002f17145d560e64f9ddda3bcbc515d8ab3a53abac25e4
MD5 ad0060c31ab53d9360df1aa2b50213a0
BLAKE2b-256 9ff14c37e2758e097f9d3e617fb0f6943add847255a7913d3919f8f9c1e804f0

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp310-cp310-win_amd64.whl.

File metadata

  • Download URL: fclx-0.7.0.8-cp310-cp310-win_amd64.whl
  • Upload date:
  • Size: 1.1 MB
  • Tags: CPython 3.10, Windows x86-64
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/4.0.2 CPython/3.11.11

File hashes

Hashes for fclx-0.7.0.8-cp310-cp310-win_amd64.whl
Algorithm Hash digest
SHA256 37852a0ac05ba9b9f889fb06a7aabd46aa72059305bf8e32773c121bae244ef2
MD5 81c2967301ae1271d857ed93b92218a6
BLAKE2b-256 82c1101aa70889bc3429a53e7457f2906e5ae3ccf7358f27e3a255e43f4783d8

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 c5523557a0f588247f34ed7a4ce53418cae3c1f671c8322ff9fa28c587a4c401
MD5 2601e5c8defffb90af8b16f2c7aa419d
BLAKE2b-256 49ba5fcd6a5ef00997b2dd6ace8e14c2a57c9595d1a31fc5aa6861940bb6b51e

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp310-cp310-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp310-cp310-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 327a13896fe389d6c48bec4110dd5d476a96e3d9402872f6594a37372dd8ac8c
MD5 aa8ff707c91965ff163c87244aaf156d
BLAKE2b-256 8a7fc36dcdddff0ea5b7a1e0749eb0b36ad7f687b6f6ee3aa99f146c1028ba80

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp310-cp310-macosx_10_9_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp310-cp310-macosx_10_9_x86_64.whl
Algorithm Hash digest
SHA256 f7e63a3c949aa1fa9bfb515a70e7f448911675471399fa7b3d09b195a4ac818f
MD5 045f973a1bfd59b7daaf167936f4f9af
BLAKE2b-256 56ff70248ff3e0920c6993b264653b458d66258364a105243491127cbf8d0038

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp39-cp39-win_amd64.whl.

File metadata

  • Download URL: fclx-0.7.0.8-cp39-cp39-win_amd64.whl
  • Upload date:
  • Size: 1.1 MB
  • Tags: CPython 3.9, Windows x86-64
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/4.0.2 CPython/3.11.11

File hashes

Hashes for fclx-0.7.0.8-cp39-cp39-win_amd64.whl
Algorithm Hash digest
SHA256 77ffcf64470996c8c6a5d105e5db6f9139cc88117f8fec696cc66f172ac422bd
MD5 3cb4707027d36e1be7f4e34da8537949
BLAKE2b-256 97cd6a7970fdbffe8908ad71aa33cbc52c3a42872279bb8dadeedd2fd600a155

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 126e3bc3676774be77cab0774900291c75308bfe0068272eccb7146a7476959f
MD5 de35deeeab5ecb21e25bdb50ba931c8d
BLAKE2b-256 fbb09b33a6830afe70f7895efddbd3f6acda974df05dda8a052d21edb0895421

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp39-cp39-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp39-cp39-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 f96a795caa7ea1ff4c17400fdbaadfe72a5f5b1c7a1d4f67616fb283bfe9a16d
MD5 05ec543cd864dca9416cd0e5c62ca887
BLAKE2b-256 de425da40a08a3dd31aac74e5549b46f239c01d0637e172577079b6772254ec0

See more details on using hashes here.

File details

Details for the file fclx-0.7.0.8-cp39-cp39-macosx_10_9_x86_64.whl.

File metadata

File hashes

Hashes for fclx-0.7.0.8-cp39-cp39-macosx_10_9_x86_64.whl
Algorithm Hash digest
SHA256 59f787b6a8605306ada091e9bf190200a9fdce65c1bea92825b300d4d33ebea3
MD5 b87e200505270ef69a15f1853f3610f5
BLAKE2b-256 43b4b92b8c1a72785bae4b74b7c16d8f622f487c2faa00a0af4ea4972d75a3a6

See more details on using hashes here.

Supported by

AWS AWS Cloud computing and Security Sponsor Datadog Datadog Monitoring Fastly Fastly CDN Google Google Download Analytics Pingdom Pingdom Monitoring Sentry Sentry Error logging StatusPage StatusPage Status page