Python API
pywavemap
A fast, efficient and accurate multi-resolution, multi-sensor 3D occupancy mapping framework.
- class pywavemap.Map
Base class for wavemap maps.
- prune
Free up memory by pruning nodes that are no longer needed. Note that this pruning operation is lossless and does not alter the estimated occupancy posterior.
- prune_smart
Similar to prune(), but avoids de-allocating nodes that were recently updated and will likely be used again in the near future.
- property size
The number of cells or nodes in the map, for fixed or multi-resolution maps, respectively.
- class pywavemap.HashedWaveletOctree
Bases:
Map
A class that stores maps using hashed wavelet octrees.
- get_cell_value
Overloaded function.
get_cell_value(self, index: numpy.ndarray[dtype=int32, shape=(3), order='C']) -> float
Query the value of the map at a given index.
get_cell_value(self, node_index: pywavemap._pywavemap_bindings.OctreeIndex) -> float
Query the value of the map at a given octree node index.
- get_cell_values
Overloaded function.
get_cell_values(self, index_list: ndarray[dtype=int32, shape=(*, 3), device='cpu']) -> numpy.ndarray[dtype=float32]
Query the map at the given indices, provided as a matrix with one (x, y, z) index per row.
get_cell_values(self, node_index_list: ndarray[dtype=int32, shape=(*, 4), device='cpu']) -> numpy.ndarray[dtype=float32]
Query the map at the given node indices, provided as a matrix with one (height, x, y, z) node index per row.
- interpolate
Overloaded function.
interpolate(self, position: numpy.ndarray[dtype=float32, shape=(3), order='C'], mode: pywavemap._pywavemap_bindings.InterpolationMode = InterpolationMode.TRILINEAR) -> float
Query the map’s value at a point, using the specified interpolation mode.
interpolate(self, position_list: ndarray[dtype=float32, shape=(*, 3), device='cpu'], mode: pywavemap._pywavemap_bindings.InterpolationMode = InterpolationMode.TRILINEAR) -> numpy.ndarray[dtype=float32]
Query the map’s value at the given points, using the specified interpolation mode.
- class pywavemap.HashedChunkedWaveletOctree
Bases:
Map
A class that stores maps using hashed chunked wavelet octrees.
- get_cell_value
Overloaded function.
get_cell_value(self, index: numpy.ndarray[dtype=int32, shape=(3), order='C']) -> float
Query the value of the map at a given index.
get_cell_value(self, node_index: pywavemap._pywavemap_bindings.OctreeIndex) -> float
Query the value of the map at a given octree node index.
- class pywavemap.OctreeIndex
A class representing indices of octree nodes.
- compute_parent_index
Overloaded function.
compute_parent_index(self) -> pywavemap._pywavemap_bindings.OctreeIndex
Compute the index of the node’s direct parent.
compute_parent_index(self, parent_height: int) -> pywavemap._pywavemap_bindings.OctreeIndex
Compute the index of the node’s parent (or ancestor) at parent_height.
- property height
The node’s resolution level in the octree. A height of 0 corresponds to the map’s maximum resolution. In a fully allocated tree, all leaf nodes are at height 0. Increasing the height by 1 doubles the node size along each dimension. The root node corresponds to the map’s lowest resolution, and the root node’s height matches the configured tree height.
- class pywavemap.Pipeline
A class to build pipelines of measurement integrators and map operations.
- run_integrators
Overloaded function.
run_integrators(self, integrator_names: typing.Sequence[str], posed_pointcloud: pywavemap._pywavemap_bindings.PosedPointcloud) -> bool
Integrate a given pointcloud.
run_integrators(self, integrator_names: typing.Sequence[str], posed_image: pywavemap._pywavemap_bindings.PosedImage) -> bool
Integrate a given depth image.
- run_pipeline
Overloaded function.
run_pipeline(self, integrator_names: typing.Sequence[str], posed_pointcloud: pywavemap._pywavemap_bindings.PosedPointcloud) -> bool
Integrate a given pointcloud, then run the map operations.
run_pipeline(self, integrator_names: typing.Sequence[str], posed_image: pywavemap._pywavemap_bindings.PosedImage) -> bool
Integrate a given depth image, then run the map operations.
convert
Submodule with common conversion functions for wavemap index types.
- convert.cell_width_to_height(cell_width: float, min_cell_width: float) int
Compute the minimum node height (resolution level) required to reacha given node width.
- param cell_width:
The desired node width.
- param min_cell_width:
The grid resolution at height 0 (max map resolution).
- convert.height_to_cell_width(min_cell_width: float, height: int) float
Compute the node width at a given height.
- param min_cell_width:
The grid resolution at height 0 (max map resolution).
- param height:
The desired height (resolution level) of the node index.
- convert.point_to_nearest_index(point: numpy.ndarray[dtype=float32, shape=(3), order='C'], cell_width: float) numpy.ndarray[dtype=int32, shape=(3), order='C']
Compute the nearest index to a point on a grid with a given cell width.
- convert.point_to_node_index(point: numpy.ndarray[dtype=float32, shape=(3), order='C'], min_cell_width: float, height: int) pywavemap._pywavemap_bindings.OctreeIndex
Compute the index of a node containing a given point.
- param min_cell_width:
The grid resolution at height 0 (max map resolution).
- param height:
The desired height (resolution level) of the node index.
logging
Submodule to configure wavemap’s logging system.
- logging.enable_prefix(enable: bool = False) None
Whether to prefix log messages with timestamps and line numbers.
param
Submodule for wavemap’s config system.