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.6.1.

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
  • Cylinder
  • Half-Space
  • Plane
  • Mesh
  • OcTree

Installation

First, install octomap, which is necessary using OcTree. For Ubuntu, using 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.

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()

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 example/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

If you're not sure about the file name format, learn more about wheel file names.

python_fcl-0.6.1-cp39-cp39-win_amd64.whl (836.8 kB view details)

Uploaded CPython 3.9Windows x86-64

python_fcl-0.6.1-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl (4.1 MB view details)

Uploaded CPython 3.9manylinux: glibc 2.12+ x86-64

python_fcl-0.6.1-cp39-cp39-macosx_10_9_x86_64.whl (1.6 MB view details)

Uploaded CPython 3.9macOS 10.9+ x86-64

python_fcl-0.6.1-cp38-cp38-win_amd64.whl (837.2 kB view details)

Uploaded CPython 3.8Windows x86-64

python_fcl-0.6.1-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl (4.2 MB view details)

Uploaded CPython 3.8manylinux: glibc 2.12+ x86-64

python_fcl-0.6.1-cp38-cp38-macosx_10_9_x86_64.whl (1.6 MB view details)

Uploaded CPython 3.8macOS 10.9+ x86-64

python_fcl-0.6.1-cp37-cp37m-win_amd64.whl (835.0 kB view details)

Uploaded CPython 3.7mWindows x86-64

python_fcl-0.6.1-cp37-cp37m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl (4.1 MB view details)

Uploaded CPython 3.7mmanylinux: glibc 2.12+ x86-64

python_fcl-0.6.1-cp37-cp37m-macosx_10_9_x86_64.whl (1.6 MB view details)

Uploaded CPython 3.7mmacOS 10.9+ x86-64

python_fcl-0.6.1-cp36-cp36m-win_amd64.whl (851.8 kB view details)

Uploaded CPython 3.6mWindows x86-64

python_fcl-0.6.1-cp36-cp36m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl (4.1 MB view details)

Uploaded CPython 3.6mmanylinux: glibc 2.12+ x86-64

python_fcl-0.6.1-cp36-cp36m-macosx_10_9_x86_64.whl (1.6 MB view details)

Uploaded CPython 3.6mmacOS 10.9+ x86-64

File details

Details for the file python_fcl-0.6.1-cp39-cp39-win_amd64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp39-cp39-win_amd64.whl
  • Upload date:
  • Size: 836.8 kB
  • Tags: CPython 3.9, Windows x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp39-cp39-win_amd64.whl
Algorithm Hash digest
SHA256 8960310f4f46ea96b17e01da21b94704cc9156efc2d3e28ec2e32143c90b8762
MD5 f6ebe3a912500b7d5c4b2e8c3da9fc5c
BLAKE2b-256 f877bc6edf4090909a0f21f83f1d37d7f208f3a5c882524b502aa4827482667a

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl.

File metadata

File hashes

Hashes for python_fcl-0.6.1-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl
Algorithm Hash digest
SHA256 d477f3f122febe8f6363ee4abd241e30a0f3ff1f7cfdc97c6f33b5a7e2272f9f
MD5 518a0f95533a689a87ac7d18e97877e0
BLAKE2b-256 37840f8ccea5480ce9e4dc80d8e8814059d8ae92c5b9a04c3fe260902fad4931

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp39-cp39-macosx_10_9_x86_64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp39-cp39-macosx_10_9_x86_64.whl
  • Upload date:
  • Size: 1.6 MB
  • Tags: CPython 3.9, macOS 10.9+ x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp39-cp39-macosx_10_9_x86_64.whl
Algorithm Hash digest
SHA256 87e23e612715591d65f8d36125dc56dc82bbbc9f2266c89ecb47c08bd073a476
MD5 1e942561567bbc85413569462e6cba63
BLAKE2b-256 1a060b38ee4ba5504ddd53405b20a10e2e2e5148b3bb69f2dc192eb95e40e6eb

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp38-cp38-win_amd64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp38-cp38-win_amd64.whl
  • Upload date:
  • Size: 837.2 kB
  • Tags: CPython 3.8, Windows x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp38-cp38-win_amd64.whl
Algorithm Hash digest
SHA256 2a1cfa75baf7075f9bd389fa618a283bd050cee7a5895307daf10691ead4c6b0
MD5 a89718ef4edd2197408500433adb02d1
BLAKE2b-256 641cb5e114e1dde05cd0903e3d5d47aa01e9d465d0af2a0d7450e0f3d03a7f97

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl.

File metadata

File hashes

Hashes for python_fcl-0.6.1-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl
Algorithm Hash digest
SHA256 a0474f3089bba31536705e810de0282ca44cccb5bb7ac6f1c308c6e610592608
MD5 3c018f2edfa6b969a5a2bc07f3734263
BLAKE2b-256 c7366fad4f84fe019be36b6c50859eed69f5caa67b5b896b8ad34b4e9171655a

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp38-cp38-macosx_10_9_x86_64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp38-cp38-macosx_10_9_x86_64.whl
  • Upload date:
  • Size: 1.6 MB
  • Tags: CPython 3.8, macOS 10.9+ x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp38-cp38-macosx_10_9_x86_64.whl
Algorithm Hash digest
SHA256 c687197cd889438e9d74bc6825d07489766290276b0be13ff17ad8d1c0c79a5f
MD5 6d4cafa1b5c0aa4d9469cd827e434bfc
BLAKE2b-256 0eb2ce3d29c696d0950d19c23224d7e45a57e451269d463e19bab0c42532b098

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp37-cp37m-win_amd64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp37-cp37m-win_amd64.whl
  • Upload date:
  • Size: 835.0 kB
  • Tags: CPython 3.7m, Windows x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp37-cp37m-win_amd64.whl
Algorithm Hash digest
SHA256 76ef429afc80e394e812947002dc4337bfbb016dec2ca4cd928dbc430bf0a5f9
MD5 895bf12a10c674ee31624a7afc8b0ed5
BLAKE2b-256 3bcc9f94725c0b844e3a50d70f6f6c9d54fb110d0c8646fd6c9dd138536d2caa

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp37-cp37m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl.

File metadata

File hashes

Hashes for python_fcl-0.6.1-cp37-cp37m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl
Algorithm Hash digest
SHA256 14e454d1a5de7a00ed165a3ce9b6182ce64a492bea5a085d3ae096961bf9ce34
MD5 55a833bcd5a00fda53d49a355829c8cf
BLAKE2b-256 1a17ae7f2f5d60c53aa21152642caa05efb131705ec1663acf8a4af7899e01c9

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp37-cp37m-macosx_10_9_x86_64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp37-cp37m-macosx_10_9_x86_64.whl
  • Upload date:
  • Size: 1.6 MB
  • Tags: CPython 3.7m, macOS 10.9+ x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp37-cp37m-macosx_10_9_x86_64.whl
Algorithm Hash digest
SHA256 650ec718b37a3337ba644392e5f34357ae381bdf3a7c39490f0896b3af134956
MD5 6805ad3ee4b086d3c62b8a39b5daa9df
BLAKE2b-256 3b06732a41d0d366ba57968ab0b2fe72140e494629c5e75c982df9d6d3405581

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp36-cp36m-win_amd64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp36-cp36m-win_amd64.whl
  • Upload date:
  • Size: 851.8 kB
  • Tags: CPython 3.6m, Windows x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp36-cp36m-win_amd64.whl
Algorithm Hash digest
SHA256 491535eeed7c919e1ba0f8cfa8c2e0c58a0273e5cf27d871bb335f01b0d363c6
MD5 51b69bde6ec359e2f36f4ee92d2a8272
BLAKE2b-256 340c281e9ad18c9daa9b342aa5d5351911a943a62bbf3d16fc0a48e2009b9fae

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp36-cp36m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl.

File metadata

File hashes

Hashes for python_fcl-0.6.1-cp36-cp36m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl
Algorithm Hash digest
SHA256 0c6fc0f2cd16836cdfb16e051e12ea93cd8307cc8c86ee61e59e79eef8d4f6a8
MD5 82e18f385c26f55e1387000ad1681e5b
BLAKE2b-256 467a99d73337a449802511a3e7803f4e748851543ea8409966694acfb5120ec6

See more details on using hashes here.

File details

Details for the file python_fcl-0.6.1-cp36-cp36m-macosx_10_9_x86_64.whl.

File metadata

  • Download URL: python_fcl-0.6.1-cp36-cp36m-macosx_10_9_x86_64.whl
  • Upload date:
  • Size: 1.6 MB
  • Tags: CPython 3.6m, macOS 10.9+ x86-64
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/3.7.1 importlib_metadata/4.10.0 pkginfo/1.8.2 requests/2.27.0 requests-toolbelt/0.9.1 tqdm/4.62.3 CPython/3.9.9

File hashes

Hashes for python_fcl-0.6.1-cp36-cp36m-macosx_10_9_x86_64.whl
Algorithm Hash digest
SHA256 8394eae83dbe997dfbc66868cc73cc5a176228959a3bfd7bdb88661672bc1071
MD5 7c0a521805ff84fea79f454ed412733a
BLAKE2b-256 e9c30e32aafb2d6cb35962223b2194dfac4af32e08d725227b185cd11fc89af7

See more details on using hashes here.

Supported by

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