Go to the documentation of this file.
3 #include <Eigen/Geometry>
21 using FlatIndex = std::size_t;
23 using GridIndex = Eigen::Vector3i;
106 const Eigen::Vector3f& origin = Eigen::Vector3f::Zero(),
112 const Eigen::Vector3f& origin = Eigen::Vector3f::Zero(),
117 const Eigen::Vector3f& voxelSize,
118 const Eigen::Vector3f& origin = Eigen::Vector3f::Zero(),
123 const Eigen::Vector3f& voxelSize,
124 const Eigen::Vector3f& origin = Eigen::Vector3f::Zero(),
151 std::size_t
getFlatIndex(
const Eigen::Vector3f& point,
bool local =
false)
const;
157 Eigen::Vector3i
getGridIndex(
const Eigen::Vector3f& point,
bool local =
false)
const;
167 Eigen::Vector3f
getVoxelCenter(
int x,
int y,
int z,
bool local =
false)
const;
201 void setCenter(
const Eigen::Vector3f& center);
233 bool isInside(
const Eigen::Vector3f& point,
bool local =
false)
const;
251 Eigen::Vector3f halfGridSize()
const;
253 Eigen::Vector3f getOriginToGridCenter(
bool local)
const;
257 Eigen::Vector3i _gridSize = Eigen::Vector3i::Zero();
259 Eigen::Vector3f _voxelSize = Eigen::Vector3f::Ones();
264 Eigen::Vector3f _origin = Eigen::Vector3f::Zero();
272 static const Eigen::IOFormat _iofVector;
274 static const Eigen::IOFormat _iofTimes;
Eigen::Vector3i getGridIndexMin() const
Get the minimal (along each axis) grid index.
Eigen::Vector3i getGridIndexMax() const
Get the maximal (along each axis) grid index.
std::size_t getFlatIndex(int x, int y, int z) const
Get the flat index for the given grid indices.
Eigen::Vector3f getVoxelSize() const
Get the voxel size.
void setGridSize(int gridSize)
Set the grid size for a cubic grid.
VoxelGridStructure()
Construct an empty grid structure (0 voxels with size 1.0).
Eigen::Quaternionf getOrientation() const
Get the grid orienation in the world frame.
void setPose(const Eigen::Matrix4f &pose)
Get the grid pose in the world frame.
Eigen::Matrix4f getPose() const
Get the grid pose in the world frame.
Eigen::Vector3f getExtentOfCenters() const
Get extent of the grid along each axis (encompassing only voxel centers).
Eigen::Vector3f getExtent() const
Get extent of the grid along each axis (encompassing the whole voxels).
Eigen::Matrix32f getLocalBoundingBoxOfCenters() const
Get the local axis aligned bounding box of the voxel centers (minimal/maximal values in columns).
bool isInside(const Eigen::Vector3i &indices) const
Indicate whether the given point is inside the voxel.
Geometric structure of a 3D voxel grid.
void Identity(MatrixXX< N, N, T > *a)
std::shared_ptr< Value > value()
Eigen::Vector3i getGridSize() const
Get the grid size.
pcl::PointIndices::Ptr indices(const PCG &g)
Retrieve the indices of the points of the point cloud stored in a point cloud graph that actually bel...
friend std::ostream & operator<<(std::ostream &os, const VoxelGridStructure &grid)
Stream a human-readable description of the grid's structure.
void setCenter(const Eigen::Vector3f ¢er)
Set the geometric center of the grid the world frame (which differs from the origin for even grid siz...
void setOrigin(const Eigen::Vector3f &value)
Set the grid origin the world frame (center of voxel [0 0 0]).
void setOrientation(const Eigen::Quaternionf &value)
Set the grid orienation in the world frame.
Eigen::Matrix4f getCenterPose() const
Get the grid pose positioned at the grid center in the world frame.
Eigen::Vector3f getVoxelCenter(std::size_t index, bool local=false) const
Get the center of the voxel with the given indices.
bool operator!=(const VoxelGridStructure &rhs) const
MatrixXX< 4, 4, float > Matrix4f
std::size_t getNumVoxels() const
Get the number of voxels contained in the structure.
Matrix< float, 3, 2 > Matrix32f
A 3x2 matrix.
void setVoxelSize(float voxelSize)
Set the voxel size for cubic voxels.
void checkIsInside(const Eigen::Vector3i &indices) const
Assert that the given indices are valid grid indices.
Eigen::Vector3f getCenter() const
Get the geometric center of the grid the world frame (which differs from the origin for even grid siz...
Eigen::Vector3f getOrigin() const
Get the grid origin in the world frame (center of voxel [0 0 0]).
Eigen::Vector3i getGridIndex(size_t index) const
Get the voxel indices of the voxel with the given index.
Eigen::Matrix32f getLocalBoundingBox() const
Get the local axis aligned bounding box of the grid (minimal/maximal values in columns).
bool operator==(const VoxelGridStructure &rhs) const
Indicates whether rhs is equal to *this.
void setCenterPose(const Eigen::Matrix4f &pose)
Set the grid pose so that the grid center is the position of the given pose under the given orientati...