Open3D (C++ API)
0.18.0+252c867
|
#include <Octree.h>
Public Member Functions | |
Octree () | |
Default Constructor. More... | |
Octree (const size_t &max_depth) | |
Parameterized Constructor. More... | |
Octree (const size_t &max_depth, const Eigen::Vector3d &origin, const double &size) | |
Parameterized Constructor. More... | |
Octree (const Octree &src_octree) | |
~Octree () override | |
Octree & | 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 |
OrientedBoundingBox | GetOrientedBoundingBox (bool robust=false) const override |
OrientedBoundingBox | GetMinimalOrientedBoundingBox (bool robust=false) const override |
Octree & | Transform (const Eigen::Matrix4d &transformation) override |
Apply transformation (4x4 matrix) to the geometry coordinates. More... | |
Octree & | Translate (const Eigen::Vector3d &translation, bool relative=true) override |
Apply translation to the geometry coordinates. More... | |
Octree & | Scale (const double scale, const Eigen::Vector3d ¢er) override |
Apply scaling to the geometry coordinates. Given a scaling factor \(s\), and center \(c\), a given point \(p\) is transformed according to \(s (p - c) + c\). More... | |
Octree & | Rotate (const Eigen::Matrix3d &R, const Eigen::Vector3d ¢er) override |
Apply rotation to the geometry coordinates and normals. Given a rotation matrix \(R\), and center \(c\), a given point \(p\) is transformed according to \(R (p - c) + c\). More... | |
bool | ConvertToJsonValue (Json::Value &value) const override |
bool | ConvertFromJsonValue (const Json::Value &value) override |
void | ConvertFromPointCloud (const geometry::PointCloud &point_cloud, double size_expand=0.01) |
Convert octree from point cloud. More... | |
void | InsertPoint (const Eigen::Vector3d &point, const std::function< std::shared_ptr< OctreeLeafNode >()> &fl_init, const std::function< void(std::shared_ptr< OctreeLeafNode >)> &fl_update, const std::function< std::shared_ptr< OctreeInternalNode >()> &fi_init=nullptr, const std::function< void(std::shared_ptr< OctreeInternalNode >)> &fi_update=nullptr) |
Insert a point to the octree. More... | |
void | Traverse (const std::function< bool(const std::shared_ptr< OctreeNode > &, const std::shared_ptr< OctreeNodeInfo > &)> &f) |
DFS traversal of Octree from the root, with callback function called for each node. More... | |
void | Traverse (const std::function< bool(const std::shared_ptr< OctreeNode > &, const std::shared_ptr< OctreeNodeInfo > &)> &f) const |
Const version of Traverse. DFS traversal of Octree from the root, with callback function called for each node. More... | |
std::pair< std::shared_ptr< OctreeLeafNode >, std::shared_ptr< OctreeNodeInfo > > | LocateLeafNode (const Eigen::Vector3d &point) const |
Returns leaf OctreeNode and OctreeNodeInfo where the querypoint should reside. More... | |
bool | operator== (const Octree &other) const |
Returns true if the Octree is completely the same, used for testing. More... | |
std::shared_ptr< geometry::VoxelGrid > | ToVoxelGrid () const |
Convert to VoxelGrid. More... | |
void | CreateFromVoxelGrid (const geometry::VoxelGrid &voxel_grid) |
Convert from voxel grid. More... | |
![]() | |
~Geometry3D () override | |
virtual Geometry3D & | Rotate (const Eigen::Matrix3d &R) |
![]() | |
virtual | ~Geometry () |
GeometryType | GetGeometryType () const |
Returns one of registered geometry types. More... | |
int | Dimension () const |
Returns whether the geometry is 2D or 3D. More... | |
std::string | GetName () const |
void | SetName (const std::string &name) |
![]() | |
virtual | ~IJsonConvertible () |
virtual std::string | ToString () const |
Convert to a styled string representation of JSON data for display. More... | |
Static Public Member Functions | |
static bool | IsPointInBound (const Eigen::Vector3d &point, const Eigen::Vector3d &origin, const double &size) |
Return true if point within bound, that is, origin <= point < origin + size. More... | |
![]() | |
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... | |
![]() | |
static bool | EigenVector3dFromJsonArray (Eigen::Vector3d &vec, const Json::Value &value) |
static bool | EigenVector3dToJsonArray (const Eigen::Vector3d &vec, Json::Value &value) |
static bool | EigenVector4dFromJsonArray (Eigen::Vector4d &vec, const Json::Value &value) |
static bool | EigenVector4dToJsonArray (const Eigen::Vector4d &vec, Json::Value &value) |
static bool | EigenMatrix3dFromJsonArray (Eigen::Matrix3d &mat, const Json::Value &value) |
static bool | EigenMatrix3dToJsonArray (const Eigen::Matrix3d &mat, Json::Value &value) |
static bool | EigenMatrix4dFromJsonArray (Eigen::Matrix4d &mat, const Json::Value &value) |
static bool | EigenMatrix4dToJsonArray (const Eigen::Matrix4d &mat, Json::Value &value) |
static bool | EigenMatrix4dFromJsonArray (Eigen::Matrix4d_u &mat, const Json::Value &value) |
static bool | EigenMatrix4dToJsonArray (const Eigen::Matrix4d_u &mat, Json::Value &value) |
static bool | EigenMatrix6dFromJsonArray (Eigen::Matrix6d &mat, const Json::Value &value) |
static bool | EigenMatrix6dToJsonArray (const Eigen::Matrix6d &mat, Json::Value &value) |
static bool | EigenMatrix6dFromJsonArray (Eigen::Matrix6d_u &mat, const Json::Value &value) |
static bool | EigenMatrix6dToJsonArray (const Eigen::Matrix6d_u &mat, Json::Value &value) |
Data Fields | |
std::shared_ptr< OctreeNode > | root_node_ = nullptr |
Root of the octree. More... | |
Eigen::Vector3d | origin_ |
double | size_ |
size_t | max_depth_ |
Additional Inherited Members | |
![]() | |
enum class | GeometryType { Unspecified = 0 , PointCloud = 1 , VoxelGrid = 2 , Octree = 3 , LineSet = 4 , MeshBase = 5 , TriangleMesh = 6 , HalfEdgeTriangleMesh = 7 , Image = 8 , RGBDImage = 9 , TetraMesh = 10 , OrientedBoundingBox = 11 , 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 | TransformCovariances (const Eigen::Matrix4d &transformation, std::vector< Eigen::Matrix3d > &covariances) const |
Transforms all covariance matrices with the transformation. 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, const Eigen::Vector3d ¢er) const |
Scale the coordinates of all points by the scaling factor scale . More... | |
void | RotatePoints (const Eigen::Matrix3d &R, std::vector< Eigen::Vector3d > &points, const Eigen::Vector3d ¢er) const |
Rotate all points with the rotation matrix R . More... | |
void | RotateNormals (const Eigen::Matrix3d &R, std::vector< Eigen::Vector3d > &normals) const |
Rotate all normals with the rotation matrix R . More... | |
void | RotateCovariances (const Eigen::Matrix3d &R, std::vector< Eigen::Matrix3d > &covariances) const |
Rotate all covariance matrices with the rotation matrix R . More... | |
![]() | |
Geometry (GeometryType type, int dimension) | |
Parameterized Constructor. More... | |
Octree datastructure.
|
inline |
Default Constructor.
|
inline |
Parameterized Constructor.
max_depth | Sets the value of the max depth of the Octree. |
|
inline |
open3d::geometry::Octree::Octree | ( | const Octree & | src_octree | ) |
|
inlineoverride |
|
overridevirtual |
Clear all elements in the geometry.
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Implements open3d::utility::IJsonConvertible.
void open3d::geometry::Octree::ConvertFromPointCloud | ( | const geometry::PointCloud & | point_cloud, |
double | size_expand = 0.01 |
||
) |
Convert octree from point cloud.
point_cloud | Input point cloud. |
size_expand | A small expansion size such that the octree is slightly bigger than the original point cloud bounds to accommodate all points. |
|
overridevirtual |
Implements open3d::utility::IJsonConvertible.
void open3d::geometry::Octree::CreateFromVoxelGrid | ( | const geometry::VoxelGrid & | voxel_grid | ) |
Convert from voxel grid.
|
overridevirtual |
Creates the axis-aligned bounding box around the object. Further details in AxisAlignedBoundingBox::AxisAlignedBoundingBox()
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 |
Creates an oriented bounding box that is identical to the axis-aligned bounding from GetAxisAlignedBoundingBox().
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Creates an oriented bounding box that is identical to the axis-aligned bounding from GetAxisAlignedBoundingBox().
Implements open3d::geometry::Geometry3D.
void open3d::geometry::Octree::InsertPoint | ( | const Eigen::Vector3d & | point, |
const std::function< std::shared_ptr< OctreeLeafNode >()> & | fl_init, | ||
const std::function< void(std::shared_ptr< OctreeLeafNode >)> & | fl_update, | ||
const std::function< std::shared_ptr< OctreeInternalNode >()> & | fi_init = nullptr , |
||
const std::function< void(std::shared_ptr< OctreeInternalNode >)> & | fi_update = nullptr |
||
) |
Insert a point to the octree.
point | Coordinates of the point. |
fl_init | Initialization fcn used to create new leaf node (if needed) associated with the point. |
fl_update | Update fcn used to update the leaf node associated with the point. |
fi_init | Initialize fcn used to create a new internal node (if needed) which is an ancestor of the point's leaf node. If omitted, the default OctreeInternalNode function is used. |
fi_update | Update fcn used to update the internal node which is an ancestor of the point's leaf node. If omitted, the default OctreeInternalNode function is used. |
|
overridevirtual |
Returns true
iff the geometry is empty.
Implements open3d::geometry::Geometry3D.
|
static |
Return true if point within bound, that is, origin <= point < origin + size.
point | Coordinates of the point. |
origin | Origin coordinates. |
size | Size of the Octree. |
std::pair< std::shared_ptr< OctreeLeafNode >, std::shared_ptr< OctreeNodeInfo > > open3d::geometry::Octree::LocateLeafNode | ( | const Eigen::Vector3d & | point | ) | const |
Returns leaf OctreeNode and OctreeNodeInfo where the querypoint should reside.
point | Coordinates of the point. |
bool open3d::geometry::Octree::operator== | ( | const Octree & | other | ) | const |
Returns true if the Octree is completely the same, used for testing.
|
overridevirtual |
Apply rotation to the geometry coordinates and normals. Given a rotation matrix \(R\), and center \(c\), a given point \(p\) is transformed according to \(R (p - c) + c\).
R | A 3x3 rotation matrix |
center | Rotation center that is used for the rotation. |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Apply scaling to the geometry coordinates. Given a scaling factor \(s\), and center \(c\), a given point \(p\) is transformed according to \(s (p - c) + c\).
scale | The scale parameter that is multiplied to the points/vertices of the geometry. |
center | Scale center that is used to resize the geometry. |
Implements open3d::geometry::Geometry3D.
std::shared_ptr< geometry::VoxelGrid > open3d::geometry::Octree::ToVoxelGrid | ( | ) | const |
Convert to VoxelGrid.
|
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.
void open3d::geometry::Octree::Traverse | ( | const std::function< bool(const std::shared_ptr< OctreeNode > &, const std::shared_ptr< OctreeNodeInfo > &)> & | f | ) |
DFS traversal of Octree from the root, with callback function called for each node.
f | Callback which fires with each traversed internal/leaf node. Arguments supply information about the node being traversed and other node-specific data. A Boolean return value is used for early-stopping. If f returns true, children of this node will not be traversed. |
void open3d::geometry::Octree::Traverse | ( | const std::function< bool(const std::shared_ptr< OctreeNode > &, const std::shared_ptr< OctreeNodeInfo > &)> & | f | ) | const |
Const version of Traverse. DFS traversal of Octree from the root, with callback function called for each node.
f | Callback which fires with each traversed internal/leaf node. Arguments supply information about the node being traversed and other node-specific data. A Boolean return value is used for early-stopping. If f returns true, children of this node will not be traversed. |
size_t open3d::geometry::Octree::max_depth_ |
Max depth of octree. The depth is defined as the distance from the deepest leaf node to root. A tree with only the root node has depth 0.
Eigen::Vector3d open3d::geometry::Octree::origin_ |
Global min bound (include). A point is within bound iff origin_ <= point < origin_ + size_.
std::shared_ptr<OctreeNode> open3d::geometry::Octree::root_node_ = nullptr |
Root of the octree.
double open3d::geometry::Octree::size_ |
Outer bounding box edge size for the whole octree. A point is within bound iff origin_ <= point < origin_ + size_.