|
|
| PointCloud (T voxalSize, bool isliveVoxel=false) |
| |
| void | setLiveVoxelGrid (bool live) |
| |
|
void | setVoxalSize (T size) |
| | Set the size of each voxel in the grid (e.g., 0.1 m for 10cm voxels).
|
| |
|
void | add (T x, T y, T z=0.0f) |
| | Add a single point.
|
| |
|
void | add (const Point3D< T > *pts, size_t count) |
| | Add from array.
|
| |
|
void | add (const Coordinate< T > &coord) |
| | Add from Coordinate.
|
| |
|
const VectorT & | points () const |
| | Provides access to the points in the point cloud.
|
| |
|
VectorT & | points () |
| | Provides access to the points in the point cloud.
|
| |
|
size_t | size () const |
| | Provide the number of points in the point cloud.
|
| |
|
bool | isEmpty () const |
| | Checks if the point cloud is empty (i.e., contains no points).
|
| |
|
Bounds | bounds () const |
| | Returns the bounding box of the point cloud, which is defined by the minimum and maximum coordinates along each axis (x, y, z). The bounding box is updated whenever new points are added to the cloud, allowing for efficient retrieval of the spatial extent of the point cloud.
|
| |
|
void | buildVoxelGrid () |
| | Builds a voxel grid for fast occupancy queries: A voxel is a grid cell.
|
| |
| std::vector< Coordinate< T > > | getNeighbors (Coordinate< T > from) const override |
| | Returns the free (unoccupied) neighboring coordinates of a given point in the voxel grid.
|
| |
| void | set3D (bool is3d) |
| |
| void | setBounds (float minX, float minY, float minZ, float maxX, float maxY, float maxZ) |
| |
|
bool | isOccupied (float x, float y, float z) const |
| | Checks if a given point is occupied based on the voxel grid.
|
| |
| bool | isValid (const Coordinate< T > &coord) const override |
| | Checks if a coordinate is valid (within bounds and not occupied)
|
| |
|
auto | beginVoxels () |
| | Provides sequential (iterator) access to all occupied voxels.
|
| |
|
auto | endVoxels () |
| | Provides sequential (iterator) access to all occupied voxels.
|
| |
|
auto | beginVoxels () const |
| | Provides sequential (iterator) access to all occupied voxels.
|
| |
|
auto | endVoxels () const |
| | Provides sequential (iterator) access to all occupied voxels.
|
| |
|
size_t | writeTo (Print &out) |
| | Write map to output.
|
| |
|
size_t | readFrom (Stream &in) |
| | Read map from input.
|
| |
|
void | clear () |
| | Clear all data.
|
| |
| virtual std::vector< Coordinate< T > > | getNeighbors (Coordinate< T > from) const =0 |
| | Get world coordinates of neighboring cells (for pathfinding or navigation).
|
| |
| virtual bool | isValid (const Coordinate< T > &coord) const =0 |
| | Check if a coordinate is inside the map bounds.
|
| |
template<typename T = DistanceM>
class tinyrobotics::PointCloud< T >
Represents a 3D point cloud for robotics and mapping applications.
The PointCloud class manages a collection of 3D points and provides:
- Efficient addition of points (individually, from arrays, or from Coordinate).
- Automatic bounding box tracking for fast spatial queries.
- Voxel grid downsampling to reduce point density while preserving structure.
- Fast occupancy queries via a voxel grid (for collision checking or mapping).
- Optional "live" voxel grid mode for real-time occupancy updates as points are added.
Usage scenarios include 3D mapping, obstacle detection, SLAM, and environment representation. The class is designed for embedded and robotics use, balancing efficiency and flexibility.
Key features:
- Add, clear, and access points.
- Retrieve the bounding box (min/max x, y, z).
- Downsample using a voxel grid (keep one point per voxel).
- Build and query a voxel occupancy grid for fast lookups.
- Optionally enable live voxel grid updates for real-time occupancy.
Example:
cloud.add(1.0, 2.0, 0.5);
cloud.buildVoxelGrid();
bool occ = cloud.isOccupied(1.0, 2.0, 0.5);
Represents a 3D point cloud for robotics and mapping applications.
Definition: PointCloud.h:64