A comprehensive Python wrapper for the OctoMap C++ library, providing efficient 3D occupancy mapping capabilities for robotics and computer vision applications. This modernized binding offers enhanced performance, bundled shared libraries for easy deployment, and seamless integration with the Python scientific ecosystem.
- 3D Occupancy Mapping: Efficient octree-based 3D occupancy mapping
- Probabilistic Updates: Stochastic occupancy updates with uncertainty handling
- Path Planning: Ray casting and collision detection
- File Operations: Save/load octree data in binary format
- Python Integration: Clean Python interface with NumPy support
- Cross-Platform: Linux native support with Windows compatibility via WSL
For most users, simply install the pre-built wheel:
pip install pyoctomapSupported Platforms:
- Linux (manylinux2014 compatible)
- Python 3.7, 3.8, 3.9, 3.10, 3.11, 3.12, 3.13, 3.14
- Pre-built wheels available for all supported combinations
🚀 ROS Integration: ROS/ROS2 integration is currently being developed on the
rosbranch, featuring ROS2 message support and real-time point cloud processing.
📋 Prerequisites: See Build System Documentation for detailed system dependencies and troubleshooting guide.
If you need to build from source or create custom wheels, we provide a Docker-based build system:
Linux / WSL (Windows Subsystem for Linux):
# Clone the repository with submodules
git clone --recursive https://github.com/Spinkoo/pyoctomap.git
cd pyoctomap
# Build and install OctoMap C++ library
cd src/octomap
mkdir build && cd build
cmake .. && make && sudo make install
# Return to main project and run automated build script
cd ../../..
chmod +x build.sh
./build.sh# Build wheels for all supported Python versions
./build-wheel.sh
# Or build manually with Docker
docker build -f docker/Dockerfile.wheel -t pyoctomap-wheel .The Docker build creates manylinux-compatible wheels for Python 3.9-3.14, properly bundling all required C++ libraries.
📋 Google Colab Users: See Build System Documentation for detailed Colab installation instructions.
import pyoctomap
import numpy as np
# Create an octree with 0.1m resolution
tree = pyoctomap.OcTree(0.1)
# Add occupied points
tree.updateNode([1.0, 2.0, 3.0], True)
tree.updateNode([1.1, 2.1, 3.1], True)
# Add free space
tree.updateNode([0.5, 0.5, 0.5], False)
# Check occupancy
node = tree.search([1.0, 2.0, 3.0])
if node and tree.isNodeOccupied(node):
print("Point is occupied!")
# Save to file
tree.write("my_map.bt")PyOctoMap provides efficient methods for dynamic mapping and probabilistic decay:
Decay and Insert Point Cloud (Recommended for Dynamic Environments):
# Recommended function for inserting scans from a moving sensor
# Solves the occluded-ghost problem by applying temporal decay before insertion
point_cloud = np.random.rand(1000, 3) * 10
sensor_origin = np.array([0.0, 0.0, 1.5])
# Tuning the decay value:
# Scans_to_Forget ≈ 4.0 / abs(logodd_decay_value)
#
# Moderate (default: -0.2): ~20 scans for ghost to fade
# Aggressive (-1.0 to -3.0): 2-4 scans (highly dynamic environments)
# Weak (-0.05 to -0.1): 40-80 scans (mostly static maps)
tree.decayAndInsertPointCloud(
point_cloud,
sensor_origin,
logodd_decay_value=-0.2, # Must be negative
max_range=50.0
)For efficient batch processing of point clouds, PyOctoMap provides both precise and fast options:
Fast Native Batching:
# Fast C++ batch insertion (full rays, optional discretization and lazy evaluation)
points = np.random.uniform(-5, 5, (1000, 3))
origin = np.array([0., 0., 0.], dtype=np.float64)
tree.insertPointCloud(points, origin, discretize=False, lazy_eval=True)
tree.updateInnerOccupancy() # Manual after lazy
# Ultra-fast version using parallel rays (no deduplication)
tree.insertPointCloudRaysFast(points, origin, max_range=50.0, lazy_eval=True)
tree.updateInnerOccupancy()Note: insertPointCloud is the standard batch insertion method. Use lazy_eval=True for performance with large point clouds, then call updateInnerOccupancy() manually afterward. All methods support NumPy arrays and max_range clipping.
| Operation | Method | Speed |
|---|---|---|
| Individual points | updateNode() |
~300,000 pts/sec |
| Batch insertion | insertPointCloud() |
~17,000 pts/sec |
| Parallel rays | insertPointCloudRaysFast() |
~30,500 pts/sec |
| Decay and insert | decayAndInsertPointCloud() |
~17,300 pts/sec |
See runnable demos in examples/:
examples/basic_test.py— smoke test for core APIexamples/demo_occupancy_grid.py— build and visualize a 2D occupancy gridexamples/demo_octomap_open3d.py— visualize octomap data with Open3Dexamples/sequential_occupancy_grid_demo.py— comprehensive sequential occupancy grid with Open3D visualizationexamples/test_sequential_occupancy_grid.py— comprehensive test suite for all occupancy grid methods
3D OctoMap Scene Visualization:
Occupancy Grid Visualization:
import pyoctomap
import numpy as np
# Create octree
tree = pyoctomap.OcTree(0.05) # 5cm resolution
sensor_origin = np.array([2.0, 2.0, 1.5])
# Add walls with ray casting
wall_points = []
for x in np.arange(0, 4.0, 0.05):
for y in np.arange(0, 4.0, 0.05):
wall_points.append([x, y, 0]) # Floor
wall_points.append([x, y, 3.0]) # Ceiling
# Use batch insertion for better performance
wall_points = np.array(wall_points)
tree.insertPointCloud(wall_points, sensor_origin, lazy_eval=True)
tree.updateInnerOccupancy()
print(f"Tree size: {tree.size()} nodes")import pyoctomap
import numpy as np
# Create an octree for path planning
tree = pyoctomap.OcTree(0.1) # 10cm resolution
# Add some obstacles to the map
obstacles = [
[1.0, 1.0, 0.5], # Wall at (1,1)
[1.5, 1.5, 0.5], # Another obstacle
[2.0, 1.0, 0.5], # Wall at (2,1)
]
for obstacle in obstacles:
tree.updateNode(obstacle, True)
def is_path_clear(start, end, tree):
"""Efficient ray casting for path planning using OctoMap's built-in castRay"""
start = np.array(start, dtype=np.float64)
end = np.array(end, dtype=np.float64)
# Calculate direction vector
direction = end - start
ray_length = np.linalg.norm(direction)
if ray_length == 0:
return True, None
# Normalize direction
direction = direction / ray_length
# Use OctoMap's efficient castRay method
end_point = np.zeros(3, dtype=np.float64)
hit = tree.castRay(start, direction, end_point,
ignoreUnknownCells=True,
maxRange=ray_length)
if hit:
# Ray hit an obstacle - path is blocked
return False, end_point
else:
# No obstacle found - path is clear
return True, None
# Check if path is clear
start = [0.5, 2.0, 0.5]
end = [2.0, 2.0, 0.5]
clear, obstacle = is_path_clear(start, end, tree)
if clear:
print("✅ Path is clear!")
else:
print(f"❌ Path blocked at: {obstacle}")
# Advanced path planning with multiple waypoints
def plan_path(waypoints, tree):
"""Plan a path through multiple waypoints using ray casting"""
path_clear = True
obstacles = []
for i in range(len(waypoints) - 1):
start = waypoints[i]
end = waypoints[i + 1]
clear, obstacle = is_path_clear(start, end, tree)
if not clear:
path_clear = False
obstacles.append((i, i+1, obstacle))
return path_clear, obstacles
# Example: Plan path through multiple waypoints
waypoints = [
[0.0, 0.0, 0.5],
[1.0, 1.0, 0.5],
[2.0, 2.0, 0.5],
[3.0, 3.0, 0.5]
]
path_clear, obstacles = plan_path(waypoints, tree)
if path_clear:
print("✅ Complete path is clear!")
else:
print(f"❌ Path blocked at segments: {obstacles}")For moving sensors in dynamic environments, use decayAndInsertPointCloud to handle occluded-ghost problems:
import pyoctomap
import numpy as np
# Create octree for dynamic mapping
tree = pyoctomap.OcTree(0.1) # 10cm resolution
# Simulate sequential scans from a moving sensor
for scan_num in range(100):
# Generate new scan (e.g., from LiDAR)
point_cloud = np.random.rand(500, 3) * 10 # Simulated point cloud
sensor_origin = np.array([scan_num * 0.1, 0.0, 1.5]) # Moving sensor
# Recommended: Decay and insert
# This solves the occluded-ghost problem by:
# 1. Applying temporal decay to occupied voxels in scan's bounding box
# 2. Inserting the new point cloud
tree.decayAndInsertPointCloud(
point_cloud,
sensor_origin,
logodd_decay_value=-0.2, # Default: ~20 scans for ghost to fade
max_range=50.0,
update_inner_occupancy=True
)
# For highly dynamic environments (faster ghost removal):
# tree.decayAndInsertPointCloud(point_cloud, sensor_origin,
# logodd_decay_value=-1.0) # ~4 scans
# Tuning guide:
# Formula: Scans_to_Forget ≈ 4.0 / abs(logodd_decay_value)
#
# - Moderate (default: -0.2): ~20 scans to fade (balanced)
# - Aggressive (-1.0 to -3.0): 2-4 scans (highly dynamic)
# - Weak (-0.05 to -0.1): 40-80 scans (mostly static)PyOctoMap provides three types of iterators for different use cases:
# Iterate over ALL nodes (inner + leaf nodes) - slower but complete
for node_it in tree.begin_tree():
coord = node_it.getCoordinate()
depth = node_it.getDepth()
size = node_it.getSize()
is_leaf = node_it.isLeaf()
# Use for: tree structure analysis, debugging, inner node operations
if not is_leaf:
print(f"Inner node at depth {depth}, size {size:.2f}m")# Iterate over LEAF nodes only - faster for occupancy queries
for leaf_it in tree.begin_leafs():
coord = leaf_it.getCoordinate()
occupied = tree.isNodeOccupied(leaf_it)
if occupied:
print(f"Occupied leaf at {coord}")
# Use for: standard occupancy operations, fast iteration# Iterate over leaf nodes within a bounding box
bbx_min = np.array([0.0, 0.0, 0.0])
bbx_max = np.array([5.0, 5.0, 5.0])
for bbx_it in tree.begin_leafs_bbx(bbx_min, bbx_max):
coord = bbx_it.getCoordinate()
print(f"Node in BBX: {coord}")
# Use for: region-specific analysis, spatial queries- Python 3.9+
- NumPy
- Cython (for building from source)
Optional for visualization:
- matplotlib (for 2D plotting)
- open3d (for 3D visualization)
- Complete API Reference - Detailed API documentation
- Build System - Prerequisites, build process, and troubleshooting
- File Format Guide - Supported file formats
- Performance Guide - Optimization tips and benchmarks
- Troubleshooting - Common issues and solutions
- Wheel Technology - Library bundling details
MIT License - see LICENSE file for details.
Contributions are welcome! Please feel free to submit issues and pull requests.
- Previous work:
wkentaro/octomap-python- This project builds upon and modernizes the original Python bindings - Core library: OctoMap - An efficient probabilistic 3D mapping framework based on octrees
- Build system: Built with Cython for seamless Python-C++ integration and performance
- Visualization: Open3D - Used for 3D visualization capabilities in demonstration scripts
- Research support: Development of this enhanced Python wrapper was supported by the French National Research Agency (ANR) under the France 2030 program, specifically the IRT Nanoelec project (ANR-10-AIRT-05), advancing robotics and 3D mapping research capabilities.


