Skip to content

Commit f653f50

Browse files
committed
Add support for OcTree, update version to 0.0.9
1 parent d85b57a commit f653f50

11 files changed

Lines changed: 72 additions & 9 deletions

File tree

MANIFEST.in

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,5 @@
11
# Include the license
22
include LICENSE
33
include fcl/fcl_defs.pxd
4+
include fcl/octomap_defs.pxd
5+
include fcl/std_defs.pxd

README.md

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,10 +23,12 @@ This package also supports most of FCL's object shapes, including:
2323
* Half-Space
2424
* Plane
2525
* Mesh
26+
* OcTree
2627

2728
## Installation
2829

29-
First, install FCL using the instructions provided [here](https://github.com/flexible-collision-library/fcl).
30+
First, install [octomap](https://github.com/OctoMap/octomap), which is necessary using OcTree. For Ubuntu, using `sudo apt-get install liboctomap-dev`
31+
Second, install FCL using the instructions provided [here](https://github.com/flexible-collision-library/fcl).
3032
If you're on Ubuntu 17.04 or newer, you can install FCL using `sudo apt-get install libfcl-dev`.
3133
Otherwise, just compile FCL from source -- it's quick and easy, and its dependencies are all easily installed via `apt` or `brew`.
3234

fcl/__init__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
from .fcl import CollisionObject, CollisionGeometry, Transform, TriangleP, Box, Sphere, Ellipsoid, Capsule, Cone, Cylinder, Halfspace, Plane, BVHModel, DynamicAABBTreeCollisionManager, collide, continuousCollide, distance, defaultCollisionCallback, defaultDistanceCallback
1+
from .fcl import CollisionObject, CollisionGeometry, Transform, TriangleP, Box, Sphere, Ellipsoid, Capsule, Cone, Cylinder, Halfspace, Plane, BVHModel, OcTree, DynamicAABBTreeCollisionManager, collide, continuousCollide, distance, defaultCollisionCallback, defaultDistanceCallback
22

33
from .collision_data import OBJECT_TYPE, NODE_TYPE, CCDMotionType, CCDSolverType, GJKSolverType, Contact, CostSource, CollisionRequest, CollisionResult, ContinuousCollisionRequest, ContinuousCollisionResult, DistanceRequest, DistanceResult, CollisionData, DistanceData
44

fcl/fcl.pyx

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,8 @@ import numpy
1111
ctypedef np.float64_t DOUBLE_t
1212

1313
cimport fcl_defs as defs
14+
cimport octomap_defs as octomap
15+
cimport std_defs as std
1416
from collision_data import Contact, CostSource, CollisionRequest, ContinuousCollisionRequest, CollisionResult, ContinuousCollisionResult, DistanceRequest, DistanceResult
1517

1618
###############################################################################
@@ -393,6 +395,18 @@ cdef class BVHModel(CollisionGeometry):
393395
else:
394396
return False
395397

398+
cdef class OcTree(CollisionGeometry):
399+
cdef octomap.OcTree* tree
400+
401+
def __cinit__(self, r, data):
402+
cdef std.stringstream ss
403+
cdef vector[char] vd = data
404+
ss.write(vd.data(), len(data))
405+
406+
self.tree = new octomap.OcTree(r)
407+
self.tree.readBinaryData(ss)
408+
self.thisptr = new defs.OcTree(defs.shared_ptr[octomap.OcTree](self.tree))
409+
396410

397411
###############################################################################
398412
# Collision managers

fcl/fcl_defs.pxd

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@ from libcpp.string cimport string
33
from libcpp.vector cimport vector
44
from libcpp.set cimport set
55
from libcpp.memory cimport shared_ptr
6+
cimport octomap_defs as octomap
67

78
cdef extern from "Python.h":
89
ctypedef struct PyObject
@@ -400,9 +401,9 @@ cdef extern from "fcl/BVH/BVH_model.h" namespace "fcl":
400401
# void computeLocalAABB()
401402

402403

403-
404-
405-
406-
407-
404+
cdef extern from "fcl/octree.h" namespace "fcl":
405+
cdef cppclass OcTree(CollisionGeometry):
406+
# Constructing
407+
OcTree(FCL_REAL resolution) except +
408+
OcTree(shared_ptr[octomap.OcTree]& tree_) except +
408409

fcl/octomap_defs.pxd

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
cimport std_defs as std
2+
3+
cdef extern from "octomap/OccupancyOcTreeBase.h" namespace "octomap":
4+
# Cython only accepts type template parameters.
5+
# see https://groups.google.com/forum/#!topic/cython-users/xAZxdCFw6Xs
6+
cdef cppclass OccupancyOcTreeBase "octomap::OccupancyOcTreeBase<octomap::OcTreeNode>" :
7+
# Constructing
8+
OccupancyOcTreeBase(double resolution) except +
9+
10+
# Reads only the data (=complete tree structure) from the input stream.
11+
# The tree needs to be constructed with the proper header information
12+
# beforehand, see readBinary().
13+
std.istream& readBinaryData(std.istream &s) except +
14+
15+
cdef extern from "octomap/OcTree.h" namespace "octomap":
16+
cdef cppclass OcTree(OccupancyOcTreeBase):
17+
# Constructing
18+
OcTree(double resolution) except +
19+

fcl/std_defs.pxd

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
2+
cdef extern from "<iostream>" namespace "std":
3+
cdef cppclass istream:
4+
istream& write(const char*, int) except +
5+
6+
cdef cppclass iostream(istream):
7+
iostream() except +
8+
9+
cdef cppclass stringstream(iostream):
10+
stringstream() except +
11+
12+

fcl/version.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
__version__ = '0.0.8'
1+
__version__ = '0.0.9'

requirements/build.bash

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,12 @@ make -j4
44
make install
55
cd ..
66

7+
cd octomap
8+
cmake .
9+
make -j4
10+
make install
11+
cd ..
12+
713
cd fcl
814
cmake .
915
make -j4

requirements/clone.bash

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,13 @@ git pull
55
git checkout 64f02f741ac94fccd0fb660a5bffcbe6d01d9939
66
cd ..
77

8+
rm -rf octomap
9+
git clone https://github.com/OctoMap/octomap.git
10+
cd octomap
11+
git pull
12+
git checkout b8c1d62a7a64ce0a5df278503f31d73acafa97e4
13+
cd ..
14+
815
rm -rf fcl
916
git clone https://github.com/flexible-collision-library/fcl.git
1017
cd fcl

0 commit comments

Comments
 (0)