Open3D (C++ API)
|
#include <VoxelGrid.h>
Public Member Functions | |
VoxelGrid () | |
VoxelGrid (const VoxelGrid &src_voxel_grid) | |
~VoxelGrid () override | |
VoxelGrid & | Clear () override |
Clear all elements in the geometry. More... | |
bool | IsEmpty () const override |
Returns true iff the geometry is empty. More... | |
Eigen::Vector3d | GetMinBound () const override |
Returns min bounds for geometry coordinates. More... | |
Eigen::Vector3d | GetMaxBound () const override |
Returns max bounds for geometry coordinates. More... | |
Eigen::Vector3d | GetCenter () const override |
Returns the center of the geometry coordinates. More... | |
AxisAlignedBoundingBox | GetAxisAlignedBoundingBox () const override |
Returns an axis-aligned bounding box of the geometry. More... | |
OrientedBoundingBox | GetOrientedBoundingBox () const override |
Returns an oriented bounding box of the geometry. More... | |
VoxelGrid & | Transform (const Eigen::Matrix4d &transformation) override |
Apply transformation (4x4 matrix) to the geometry coordinates. More... | |
VoxelGrid & | Translate (const Eigen::Vector3d &translation, bool relative=true) override |
Apply translation to the geometry coordinates. More... | |
VoxelGrid & | Scale (const double scale, bool center=true) override |
Apply scaling to the geometry coordinates. More... | |
VoxelGrid & | Rotate (const Eigen::Matrix3d &R, bool center=true) override |
Apply rotation to the geometry coordinates and normals. More... | |
VoxelGrid & | operator+= (const VoxelGrid &voxelgrid) |
VoxelGrid | operator+ (const VoxelGrid &voxelgrid) const |
bool | HasVoxels () const |
bool | HasColors () const |
Eigen::Vector3i | GetVoxel (const Eigen::Vector3d &point) const |
Eigen::Vector3d | GetVoxelCenterCoordinate (const Eigen::Vector3i &idx) const |
void | AddVoxel (const Voxel &voxel) |
Add a voxel with specified grid index and color. More... | |
std::vector< Eigen::Vector3d > | GetVoxelBoundingPoints (const Eigen::Vector3i &index) const |
Return a vector of 3D coordinates that define the indexed voxel cube. More... | |
std::vector< bool > | CheckIfIncluded (const std::vector< Eigen::Vector3d > &queries) |
VoxelGrid & | CarveDepthMap (const Image &depth_map, const camera::PinholeCameraParameters &camera_parameter) |
VoxelGrid & | CarveSilhouette (const Image &silhouette_mask, const camera::PinholeCameraParameters &camera_parameter) |
void | CreateFromOctree (const Octree &octree) |
std::shared_ptr< geometry::Octree > | ToOctree (const size_t &max_depth) const |
![]() | |
~Geometry3D () override | |
![]() | |
virtual | ~Geometry () |
GeometryType | GetGeometryType () const |
Returns one of registered geometry types. More... | |
int | Dimension () const |
Returns whether the geometry is 2D or 3D. More... | |
Static Public Member Functions | |
static std::shared_ptr< VoxelGrid > | CreateDense (const Eigen::Vector3d &origin, double voxel_size, double width, double height, double depth) |
static std::shared_ptr< VoxelGrid > | CreateFromPointCloud (const PointCloud &input, double voxel_size) |
static std::shared_ptr< VoxelGrid > | CreateFromPointCloudWithinBounds (const PointCloud &input, double voxel_size, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound) |
static std::shared_ptr< VoxelGrid > | CreateFromTriangleMesh (const TriangleMesh &input, double voxel_size) |
static std::shared_ptr< VoxelGrid > | CreateFromTriangleMeshWithinBounds (const TriangleMesh &input, double voxel_size, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound) |
![]() | |
static Eigen::Matrix3d | GetRotationMatrixFromXYZ (const Eigen::Vector3d &rotation) |
Get Rotation Matrix from XYZ RotationType. More... | |
static Eigen::Matrix3d | GetRotationMatrixFromYZX (const Eigen::Vector3d &rotation) |
Get Rotation Matrix from YZX RotationType. More... | |
static Eigen::Matrix3d | GetRotationMatrixFromZXY (const Eigen::Vector3d &rotation) |
Get Rotation Matrix from ZXY RotationType. More... | |
static Eigen::Matrix3d | GetRotationMatrixFromXZY (const Eigen::Vector3d &rotation) |
Get Rotation Matrix from XZY RotationType. More... | |
static Eigen::Matrix3d | GetRotationMatrixFromZYX (const Eigen::Vector3d &rotation) |
Get Rotation Matrix from ZYX RotationType. More... | |
static Eigen::Matrix3d | GetRotationMatrixFromYXZ (const Eigen::Vector3d &rotation) |
Get Rotation Matrix from YXZ RotationType. More... | |
static Eigen::Matrix3d | GetRotationMatrixFromAxisAngle (const Eigen::Vector3d &rotation) |
Get Rotation Matrix from AxisAngle RotationType. More... | |
static Eigen::Matrix3d | GetRotationMatrixFromQuaternion (const Eigen::Vector4d &rotation) |
Get Rotation Matrix from Quaternion. More... | |
Data Fields | |
double | voxel_size_ = 0.0 |
Eigen::Vector3d | origin_ = Eigen::Vector3d::Zero() |
std::unordered_map< Eigen::Vector3i, Voxel, utility::hash_eigen::hash< Eigen::Vector3i > > | voxels_ |
Additional Inherited Members | |
![]() | |
enum | GeometryType { GeometryType::Unspecified = 0, GeometryType::PointCloud = 1, GeometryType::VoxelGrid = 2, GeometryType::Octree = 3, GeometryType::LineSet = 4, GeometryType::MeshBase = 5, GeometryType::TriangleMesh = 6, GeometryType::HalfEdgeTriangleMesh = 7, GeometryType::Image = 8, GeometryType::RGBDImage = 9, GeometryType::TetraMesh = 10, GeometryType::OrientedBoundingBox = 11, GeometryType::AxisAlignedBoundingBox = 12 } |
Specifies possible geometry types. More... | |
![]() | |
Geometry3D (GeometryType type) | |
Parameterized Constructor. More... | |
Eigen::Vector3d | ComputeMinBound (const std::vector< Eigen::Vector3d > &points) const |
Compute min bound of a list points. More... | |
Eigen::Vector3d | ComputeMaxBound (const std::vector< Eigen::Vector3d > &points) const |
Compute max bound of a list points. More... | |
Eigen::Vector3d | ComputeCenter (const std::vector< Eigen::Vector3d > &points) const |
Computer center of a list of points. More... | |
void | ResizeAndPaintUniformColor (std::vector< Eigen::Vector3d > &colors, const size_t size, const Eigen::Vector3d &color) const |
Resizes the colors vector and paints a uniform color. More... | |
void | TransformPoints (const Eigen::Matrix4d &transformation, std::vector< Eigen::Vector3d > &points) const |
Transforms all points with the transformation matrix. More... | |
void | TransformNormals (const Eigen::Matrix4d &transformation, std::vector< Eigen::Vector3d > &normals) const |
Transforms the normals with the transformation matrix. More... | |
void | TranslatePoints (const Eigen::Vector3d &translation, std::vector< Eigen::Vector3d > &points, bool relative) const |
Apply translation to the geometry coordinates. More... | |
void | ScalePoints (const double scale, std::vector< Eigen::Vector3d > &points, bool center) const |
Scale the coordinates of all points by the scaling factor scale . More... | |
void | RotatePoints (const Eigen::Matrix3d &R, std::vector< Eigen::Vector3d > &points, bool center) const |
Rotate all points with the rotation matrix R . More... | |
void | RotateNormals (const Eigen::Matrix3d &R, std::vector< Eigen::Vector3d > &normals, bool center) const |
Rotate all normals with the rotation matrix R . More... | |
![]() | |
Geometry (GeometryType type, int dimension) | |
Parameterized Constructor. More... | |
|
inline |
open3d::geometry::VoxelGrid::VoxelGrid | ( | const VoxelGrid & | src_voxel_grid | ) |
|
inlineoverride |
void open3d::geometry::VoxelGrid::AddVoxel | ( | const Voxel & | voxel | ) |
Add a voxel with specified grid index and color.
VoxelGrid & open3d::geometry::VoxelGrid::CarveDepthMap | ( | const Image & | depth_map, |
const camera::PinholeCameraParameters & | camera_parameter | ||
) |
Remove all voxels from the VoxelGrid where none of the boundary points of the voxel projects to depth value that is smaller, or equal than the projected depth of the boundary point. The point is not carved if none of the boundary points of the voxel projects to a valid image location.
VoxelGrid & open3d::geometry::VoxelGrid::CarveSilhouette | ( | const Image & | silhouette_mask, |
const camera::PinholeCameraParameters & | camera_parameter | ||
) |
Remove all voxels from the VoxelGrid where none of the boundary points of the voxel projects to a valid mask pixel (pixel value > 0). The point is not carved if none of the boundary points of the voxel projects to a valid image location.
std::vector< bool > open3d::geometry::VoxelGrid::CheckIfIncluded | ( | const std::vector< Eigen::Vector3d > & | queries | ) |
|
overridevirtual |
Clear all elements in the geometry.
Implements open3d::geometry::Geometry3D.
|
static |
void open3d::geometry::VoxelGrid::CreateFromOctree | ( | const Octree & | octree | ) |
|
static |
|
static |
|
static |
|
static |
|
overridevirtual |
Returns an axis-aligned bounding box of the geometry.
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Returns the center of the geometry coordinates.
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Returns max bounds for geometry coordinates.
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Returns min bounds for geometry coordinates.
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Returns an oriented bounding box of the geometry.
Implements open3d::geometry::Geometry3D.
Eigen::Vector3i open3d::geometry::VoxelGrid::GetVoxel | ( | const Eigen::Vector3d & | point | ) | const |
std::vector< Eigen::Vector3d > open3d::geometry::VoxelGrid::GetVoxelBoundingPoints | ( | const Eigen::Vector3i & | index | ) | const |
Return a vector of 3D coordinates that define the indexed voxel cube.
|
inline |
|
inline |
|
inline |
|
overridevirtual |
Returns true
iff the geometry is empty.
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Apply rotation to the geometry coordinates and normals.
R | A 3D vector that either defines the three angles for Euler rotation, or in the axis-angle representation the normalized vector defines the axis of rotation and the norm the angle around this axis. |
center | If true , the rotation is applied relative to the center of the geometry. Otherwise, the rotation is directly applied to the geometry, i.e. relative to the origin. |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Apply scaling to the geometry coordinates.
scale | The scale parameter that is multiplied to the points/vertices of the geometry. |
center | If true , the scale is applied relative to the center of the geometry. Otherwise, the scale is directly applied to the geometry, i.e. relative to the origin. |
Implements open3d::geometry::Geometry3D.
std::shared_ptr< geometry::Octree > open3d::geometry::VoxelGrid::ToOctree | ( | const size_t & | max_depth | ) | const |
|
overridevirtual |
Apply transformation (4x4 matrix) to the geometry coordinates.
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Apply translation to the geometry coordinates.
translation | A 3D vector to transform the geometry. |
relative | If true , the translation is directly applied to the geometry. Otherwise, the geometry center is moved to the translation . |
Implements open3d::geometry::Geometry3D.
Eigen::Vector3d open3d::geometry::VoxelGrid::origin_ = Eigen::Vector3d::Zero() |
double open3d::geometry::VoxelGrid::voxel_size_ = 0.0 |
std::unordered_map<Eigen::Vector3i, Voxel, utility::hash_eigen::hash<Eigen::Vector3i> > open3d::geometry::VoxelGrid::voxels_ |