#include <ndt_map.hpp>
|
| auto | index (const Point &pt) const |
| |
| VoxelT & | voxel (uint64_t idx) |
| |
| auto | emplace (uint64_t key, const VoxelT &&vx) |
| |
| const Derived & | impl () const |
| |
| Derived & | impl () |
| |
◆ Config
template<typename Derived , typename VoxelT >
◆ Grid
template<typename Derived , typename VoxelT >
◆ Point
template<typename Derived , typename VoxelT >
◆ TimePoint
template<typename Derived , typename VoxelT >
◆ VoxelViewVector
template<typename Derived , typename VoxelT >
◆ NDTMapBase() [1/3]
template<typename Derived , typename VoxelT >
Constructor
- Parameters
-
| voxel_grid_config | Voxel grid config to configure the underlying voxel grid. |
◆ NDTMapBase() [2/3]
template<typename Derived , typename VoxelT >
◆ NDTMapBase() [3/3]
template<typename Derived , typename VoxelT >
◆ begin() [1/2]
template<typename Derived , typename VoxelT >
Returns an const iterator to the first element of the map.
- Returns
- Iterator
◆ begin() [2/2]
template<typename Derived , typename VoxelT >
Returns an iterator to the first element of the map.
- Returns
- Iterator
◆ cbegin()
template<typename Derived , typename VoxelT >
Returns a const iterator to the first element of the map.
- Returns
- Iterator
◆ cell() [1/2]
template<typename Derived , typename VoxelT >
Lookup the cell at location.
- Parameters
-
- Returns
- A vector containing the cell at given coordinates. A vector is used to support near-neighbour cell queries in the future.
◆ cell() [2/2]
template<typename Derived , typename VoxelT >
Lookup the cell at location.
- Parameters
-
| x | x coordinate |
| y | y coordinate |
| z | z coordinate |
- Returns
- A vector containing the cell at given coordinates. A vector is used to support near-neighbour cell queries in the future.
◆ cell_size()
template<typename Derived , typename VoxelT >
Get size of the cell.
- Returns
- A point representing the dimensions of the cell.
◆ cend()
template<typename Derived , typename VoxelT >
Returns a const iterator to one past the last element of the map.
- Returns
- Iterator
◆ clear()
template<typename Derived , typename VoxelT >
Clear all voxels in the map.
◆ emplace()
template<typename Derived , typename VoxelT >
◆ end() [1/2]
template<typename Derived , typename VoxelT >
Returns a const iterator to one past the last element of the map.
- Returns
- Iterator
◆ end() [2/2]
template<typename Derived , typename VoxelT >
Returns an iterator to one past the last element of the map.
- Returns
- Iterator
◆ frame_id()
template<typename Derived , typename VoxelT >
Get map's frame id.
- Returns
- Frame id of the map.
◆ index()
template<typename Derived , typename VoxelT >
Get voxel index given a point.
- Parameters
-
- Returns
- voxel index
◆ insert()
template<typename Derived , typename VoxelT >
Insert a point cloud to the map.
- Parameters
-
| msg | PointCloud2 message to add. |
◆ operator=() [1/2]
template<typename Derived , typename VoxelT >
◆ operator=() [2/2]
template<typename Derived , typename VoxelT >
◆ size()
template<typename Derived , typename VoxelT >
Get size of the map
- Returns
- Number of voxels in the map. This number includes the voxels that do not have enough numbers to be used yet.
◆ stamp()
template<typename Derived , typename VoxelT >
Get map's time stamp.
- Returns
- map's time stamp.
◆ voxel()
template<typename Derived , typename VoxelT >
Get a reference to the voxel at the given index. If no voxel exists, a default constructed Voxel is inserted.
- Parameters
-
- Returns
The documentation for this class was generated from the following file: