|
Open3D (C++ API)
|
Data Structures | |
| class | Geometry |
| class | Geometry2D |
| class | Geometry3D |
| class | HalfEdgeTriangleMesh |
| class | Image |
| class | KDTreeFlann |
| class | KDTreeSearchParam |
| class | KDTreeSearchParamHybrid |
| class | KDTreeSearchParamKNN |
| class | KDTreeSearchParamRadius |
| class | LineSet |
| class | PointCloud |
| class | RGBDImage |
| class | TriangleMesh |
| class | VoxelGrid |
Typedefs | |
| typedef std::vector< std::shared_ptr< Image > > | ImagePyramid |
| Typedef and functions for ImagePyramid. More... | |
| typedef std::vector< std::shared_ptr< RGBDImage > > | RGBDImagePyramid |
| Typedef and functions for RGBDImagePyramid. More... | |
Functions | |
| std::shared_ptr< PointCloud > | SelectDownSample (const PointCloud &input, const std::vector< size_t > &indices, bool invert) |
| std::shared_ptr< TriangleMesh > | SelectDownSample (const TriangleMesh &input, const std::vector< size_t > &indices) |
| std::shared_ptr< PointCloud > | VoxelDownSample (const PointCloud &input, double voxel_size) |
| std::tuple< std::shared_ptr< PointCloud >, Eigen::MatrixXi > | VoxelDownSampleAndTrace (const PointCloud &input, double voxel_size, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound, bool approximate_class) |
| std::shared_ptr< PointCloud > | UniformDownSample (const PointCloud &input, size_t every_k_points) |
| std::shared_ptr< PointCloud > | CropPointCloud (const PointCloud &input, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound) |
| std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > | RemoveRadiusOutliers (const PointCloud &input, size_t nb_points, double search_radius) |
| std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > | RemoveStatisticalOutliers (const PointCloud &input, size_t nb_neighbors, double std_ratio) |
| std::shared_ptr< TriangleMesh > | CropTriangleMesh (const TriangleMesh &input, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound) |
| bool | EstimateNormals (PointCloud &cloud, const KDTreeSearchParam &search_param) |
| bool | OrientNormalsToAlignWithDirection (PointCloud &cloud, const Eigen::Vector3d &orientation_reference) |
| bool | OrientNormalsTowardsCameraLocation (PointCloud &cloud, const Eigen::Vector3d &camera_location) |
| std::shared_ptr< HalfEdgeTriangleMesh > | CreateHalfEdgeMeshFromMesh (const TriangleMesh &mesh) |
| template<typename T > | |
| T * | PointerAt (const Image &image, int u, int v) |
| Function to access the raw data of a single-channel Image. More... | |
| template float * | PointerAt< float > (const Image &image, int u, int v) |
| template int * | PointerAt< int > (const Image &image, int u, int v) |
| template uint8_t * | PointerAt< uint8_t > (const Image &image, int u, int v) |
| template uint16_t * | PointerAt< uint16_t > (const Image &image, int u, int v) |
| template<typename T > | |
| T * | PointerAt (const Image &image, int u, int v, int ch) |
| Function to access the raw data of a multi-channel Image. More... | |
| template float * | PointerAt< float > (const Image &image, int u, int v, int ch) |
| template int * | PointerAt< int > (const Image &image, int u, int v, int ch) |
| template uint8_t * | PointerAt< uint8_t > (const Image &image, int u, int v, int ch) |
| template uint16_t * | PointerAt< uint16_t > (const Image &image, int u, int v, int ch) |
| std::shared_ptr< Image > | ConvertDepthToFloatImage (const Image &depth, double depth_scale, double depth_trunc) |
| void | ClipIntensityImage (Image &input, double min, double max) |
| void | LinearTransformImage (Image &input, double scale, double offset) |
| std::shared_ptr< Image > | DownsampleImage (const Image &input) |
| Function to 2x image downsample using simple 2x2 averaging. More... | |
| std::shared_ptr< Image > | FilterHorizontalImage (const Image &input, const std::vector< double > &kernel) |
| std::shared_ptr< Image > | FilterImage (const Image &input, Image::FilterType type) |
| Function to filter image with pre-defined filtering type. More... | |
| ImagePyramid | FilterImagePyramid (const ImagePyramid &input, Image::FilterType type) |
| Function to filter image pyramid. More... | |
| std::shared_ptr< Image > | FilterImage (const Image &input, const std::vector< double > &dx, const std::vector< double > &dy) |
| Function to filter image with arbitrary dx, dy separable filters. More... | |
| std::shared_ptr< Image > | FlipImage (const Image &input) |
| std::shared_ptr< Image > | DilateImage (const Image &input, int half_kernel_size=1) |
| Function to dilate 8bit mask map. More... | |
| std::shared_ptr< Image > | CreateDepthBoundaryMask (const Image &depth_image_input, double depth_threshold_for_discontinuity_check=0.1, int half_dilation_kernel_size_for_discontinuity_map=3) |
| Function to create a depthmap boundary mask from depth image. More... | |
| std::shared_ptr< Image > | CreateDepthToCameraDistanceMultiplierFloatImage (const camera::PinholeCameraIntrinsic &intrinsic) |
| std::shared_ptr< Image > | CreateFloatImageFromImage (const Image &image, Image::ColorToIntensityConversionType type=Image::ColorToIntensityConversionType::Weighted) |
| Return a gray scaled float type image. More... | |
| template<typename T > | |
| std::shared_ptr< Image > | CreateImageFromFloatImage (const Image &input) |
| ImagePyramid | CreateImagePyramid (const Image &image, size_t num_of_levels, bool with_gaussian_filter=true) |
| Function to create image pyramid. More... | |
| template std::shared_ptr< Image > | CreateImageFromFloatImage< uint8_t > (const Image &input) |
| template std::shared_ptr< Image > | CreateImageFromFloatImage< uint16_t > (const Image &input) |
| template int | KDTreeFlann::Search< Eigen::Vector3d > (const Eigen::Vector3d &query, const KDTreeSearchParam ¶m, std::vector< int > &indices, std::vector< double > &distance2) const |
| template int | KDTreeFlann::SearchKNN< Eigen::Vector3d > (const Eigen::Vector3d &query, int knn, std::vector< int > &indices, std::vector< double > &distance2) const |
| template int | KDTreeFlann::SearchRadius< Eigen::Vector3d > (const Eigen::Vector3d &query, double radius, std::vector< int > &indices, std::vector< double > &distance2) const |
| template int | KDTreeFlann::SearchHybrid< Eigen::Vector3d > (const Eigen::Vector3d &query, double radius, int max_nn, std::vector< int > &indices, std::vector< double > &distance2) const |
| template int | KDTreeFlann::Search< Eigen::VectorXd > (const Eigen::VectorXd &query, const KDTreeSearchParam ¶m, std::vector< int > &indices, std::vector< double > &distance2) const |
| template int | KDTreeFlann::SearchKNN< Eigen::VectorXd > (const Eigen::VectorXd &query, int knn, std::vector< int > &indices, std::vector< double > &distance2) const |
| template int | KDTreeFlann::SearchRadius< Eigen::VectorXd > (const Eigen::VectorXd &query, double radius, std::vector< int > &indices, std::vector< double > &distance2) const |
| template int | KDTreeFlann::SearchHybrid< Eigen::VectorXd > (const Eigen::VectorXd &query, double radius, int max_nn, std::vector< int > &indices, std::vector< double > &distance2) const |
| std::shared_ptr< LineSet > | CreateLineSetFromPointCloudCorrespondences (const PointCloud &cloud0, const PointCloud &cloud1, const std::vector< std::pair< int, int >> &correspondences) |
| std::vector< double > | ComputePointCloudToPointCloudDistance (const PointCloud &source, const PointCloud &target) |
| std::tuple< Eigen::Vector3d, Eigen::Matrix3d > | ComputePointCloudMeanAndCovariance (const PointCloud &input) |
| std::vector< double > | ComputePointCloudMahalanobisDistance (const PointCloud &input) |
| std::vector< double > | ComputePointCloudNearestNeighborDistance (const PointCloud &input) |
| std::shared_ptr< PointCloud > | CreatePointCloudFromDepthImage (const Image &depth, const camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity(), double depth_scale=1000.0, double depth_trunc=1000.0, int stride=1) |
| std::shared_ptr< PointCloud > | CreatePointCloudFromRGBDImage (const RGBDImage &image, const camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity()) |
| RGBDImagePyramid | FilterRGBDImagePyramid (const RGBDImagePyramid &rgbd_image_pyramid, Image::FilterType type) |
| RGBDImagePyramid | CreateRGBDImagePyramid (const RGBDImage &rgbd_image, size_t num_of_levels, bool with_gaussian_filter_for_color, bool with_gaussian_filter_for_depth) |
| std::shared_ptr< RGBDImage > | CreateRGBDImageFromColorAndDepth (const Image &color, const Image &depth, double depth_scale=1000.0, double depth_trunc=3.0, bool convert_rgb_to_intensity=true) |
| Factory function to create an RGBD Image from color and depth Images. More... | |
| std::shared_ptr< RGBDImage > | CreateRGBDImageFromRedwoodFormat (const Image &color, const Image &depth, bool convert_rgb_to_intensity=true) |
| Factory function to create an RGBD Image from Redwood dataset. More... | |
| std::shared_ptr< RGBDImage > | CreateRGBDImageFromTUMFormat (const Image &color, const Image &depth, bool convert_rgb_to_intensity=true) |
| Factory function to create an RGBD Image from TUM dataset. More... | |
| std::shared_ptr< RGBDImage > | CreateRGBDImageFromSUNFormat (const Image &color, const Image &depth, bool convert_rgb_to_intensity=true) |
| Factory function to create an RGBD Image from SUN3D dataset. More... | |
| std::shared_ptr< RGBDImage > | CreateRGBDImageFromNYUFormat (const Image &color, const Image &depth, bool convert_rgb_to_intensity=true) |
| Factory function to create an RGBD Image from NYU dataset. More... | |
| std::shared_ptr< TriangleMesh > | CreateMeshBox (double width=1.0, double height=1.0, double depth=1.0) |
| std::shared_ptr< TriangleMesh > | CreateMeshSphere (double radius=1.0, int resolution=20) |
| std::shared_ptr< TriangleMesh > | CreateMeshCylinder (double radius=1.0, double height=2.0, int resolution=20, int split=4) |
| std::shared_ptr< TriangleMesh > | CreateMeshCone (double radius=1.0, double height=2.0, int resolution=20, int split=1) |
| std::shared_ptr< TriangleMesh > | CreateMeshArrow (double cylinder_radius=1.0, double cone_radius=1.5, double cylinder_height=5.0, double cone_height=4.0, int resolution=20, int cylinder_split=4, int cone_split=1) |
| std::shared_ptr< TriangleMesh > | CreateMeshCoordinateFrame (double size=1.0, const Eigen::Vector3d &origin=Eigen::Vector3d(0.0, 0.0, 0.0)) |
| std::shared_ptr< VoxelGrid > | CreateSurfaceVoxelGridFromPointCloud (const PointCloud &input, double voxel_size) |
| typedef std::vector<std::shared_ptr<Image> > open3d::geometry::ImagePyramid |
Typedef and functions for ImagePyramid.
| typedef std::vector<std::shared_ptr<RGBDImage> > open3d::geometry::RGBDImagePyramid |
Typedef and functions for RGBDImagePyramid.
| void open3d::geometry::ClipIntensityImage | ( | Image & | input, |
| double | min = 0.0, |
||
| double | max = 1.0 |
||
| ) |
Function to clipping pixel intensities min is lower bound max is upper bound
| std::vector< double > open3d::geometry::ComputePointCloudMahalanobisDistance | ( | const PointCloud & | input | ) |
Function to compute the Mahalanobis distance for points in an
| input | point cloud https://en.wikipedia.org/wiki/Mahalanobis_distance |
| std::tuple< Eigen::Vector3d, Eigen::Matrix3d > open3d::geometry::ComputePointCloudMeanAndCovariance | ( | const PointCloud & | input | ) |
Function to compute the mean and covariance matrix of an
| input | point cloud |
| std::vector< double > open3d::geometry::ComputePointCloudNearestNeighborDistance | ( | const PointCloud & | input | ) |
Function to compute the distance from a point to its nearest neighbor in the
| input | point cloud |
| std::vector< double > open3d::geometry::ComputePointCloudToPointCloudDistance | ( | const PointCloud & | source, |
| const PointCloud & | target | ||
| ) |
Function to compute the point to point distances between point clouds
| source | is the first point cloud. |
| target | is the second point cloud. |
| source |
| std::shared_ptr< Image > open3d::geometry::ConvertDepthToFloatImage | ( | const Image & | depth, |
| double | depth_scale, | ||
| double | depth_trunc | ||
| ) |
| std::shared_ptr< Image > open3d::geometry::CreateDepthBoundaryMask | ( | const Image & | depth_image_input, |
| double | depth_threshold_for_discontinuity_check, | ||
| int | half_dilation_kernel_size_for_discontinuity_map | ||
| ) |
Function to create a depthmap boundary mask from depth image.
| std::shared_ptr< Image > open3d::geometry::CreateDepthToCameraDistanceMultiplierFloatImage | ( | const camera::PinholeCameraIntrinsic & | intrinsic | ) |
Factory function to create a float image composed of multipliers that convert depth values into camera distances (ImageFactory.cpp) The multiplier function M(u,v) is defined as: M(u, v) = sqrt(1 + ((u - cx) / fx) ^ 2 + ((v - cy) / fy) ^ 2) This function is used as a convenient function for performance optimization in volumetric integration (see Core/Integration/TSDFVolume.h).
| std::shared_ptr< Image > open3d::geometry::CreateFloatImageFromImage | ( | const Image & | image, |
| Image::ColorToIntensityConversionType | type = Image::ColorToIntensityConversionType::Weighted |
||
| ) |
Return a gray scaled float type image.
| std::shared_ptr< HalfEdgeTriangleMesh > open3d::geometry::CreateHalfEdgeMeshFromMesh | ( | const TriangleMesh & | mesh | ) |
| std::shared_ptr< Image > open3d::geometry::CreateImageFromFloatImage | ( | const Image & | input | ) |
Function to change data types of image crafted for specific usage such as single channel float image -> 8-bit RGB or 16-bit depth image
| template std::shared_ptr<Image> open3d::geometry::CreateImageFromFloatImage< uint16_t > | ( | const Image & | input | ) |
| template std::shared_ptr<Image> open3d::geometry::CreateImageFromFloatImage< uint8_t > | ( | const Image & | input | ) |
| ImagePyramid open3d::geometry::CreateImagePyramid | ( | const Image & | image, |
| size_t | num_of_levels, | ||
| bool | with_gaussian_filter = true |
||
| ) |
Function to create image pyramid.
| std::shared_ptr< LineSet > open3d::geometry::CreateLineSetFromPointCloudCorrespondences | ( | const PointCloud & | cloud0, |
| const PointCloud & | cloud1, | ||
| const std::vector< std::pair< int, int >> & | correspondences | ||
| ) |
Factory function to create a lineset from two pointclouds and a correspondence set (LineSetFactory.cpp)
| std::shared_ptr< TriangleMesh > open3d::geometry::CreateMeshArrow | ( | double | cylinder_radius = 1.0, |
| double | cone_radius = 1.5, |
||
| double | cylinder_height = 5.0, |
||
| double | cone_height = 4.0, |
||
| int | resolution = 20, |
||
| int | cylinder_split = 4, |
||
| int | cone_split = 1 |
||
| ) |
Factory function to create an arrow mesh (TriangleMeshFactory.cpp) The axis of the cone with
| cone_radius | will be along the z-axis. The cylinder with |
| cylinder_radius | is from (0, 0, 0) to (0, 0, cylinder_height), and the cone is from (0, 0, cylinder_height) to (0, 0, cylinder_height + cone_height). The cone will be split into |
| resolution | segments. The |
| cylinder_height | will be split into |
| cylinder_split | segments. The |
| cone_height | will be split into |
| cone_split | segments. |
| std::shared_ptr< TriangleMesh > open3d::geometry::CreateMeshBox | ( | double | width = 1.0, |
| double | height = 1.0, |
||
| double | depth = 1.0 |
||
| ) |
Factory function to create a box mesh (TriangleMeshFactory.cpp) The left bottom corner on the front will be placed at (0, 0, 0). The
| width | is x-directional length, and |
| height | and |
| depth | are y- and z-directional lengths respectively. |
| std::shared_ptr< TriangleMesh > open3d::geometry::CreateMeshCone | ( | double | radius = 1.0, |
| double | height = 2.0, |
||
| int | resolution = 20, |
||
| int | split = 1 |
||
| ) |
Factory function to create a cone mesh (TriangleMeshFactory.cpp) The axis of the cone will be from (0, 0, 0) to (0, 0,
| height). | The circle with |
| radius | will be split into |
| resolution | segments. The height will be split into |
| split | segments. |
| std::shared_ptr< TriangleMesh > open3d::geometry::CreateMeshCoordinateFrame | ( | double | size = 1.0, |
| const Eigen::Vector3d & | origin = Eigen::Vector3d(0.0, 0.0, 0.0) |
||
| ) |
Factory function to create a coordinate frame mesh (TriangleMeshFactory.cpp) The coordinate frame will be centered at
| origin | The x, y, z axis will be rendered as red, green, and blue arrows respectively. |
| size | is the length of the axes. |
| std::shared_ptr< TriangleMesh > open3d::geometry::CreateMeshCylinder | ( | double | radius = 1.0, |
| double | height = 2.0, |
||
| int | resolution = 20, |
||
| int | split = 4 |
||
| ) |
Factory function to create a cylinder mesh (TriangleMeshFactory.cpp) The axis of the cylinder will be from (0, 0, -height/2) to (0, 0, height/2). The circle with
| radius | will be split into |
| resolution | segments. The |
| height | will be split into |
| split | segments. |
| std::shared_ptr< TriangleMesh > open3d::geometry::CreateMeshSphere | ( | double | radius = 1.0, |
| int | resolution = 20 |
||
| ) |
Factory function to create a sphere mesh (TriangleMeshFactory.cpp) The sphere with
| radius | will be centered at (0, 0, 0). Its axis is aligned with z-axis. The longitudes will be split into |
| resolution | segments. The latitudes will be split into |
| resolution | * 2 segments. |
| std::shared_ptr< PointCloud > open3d::geometry::CreatePointCloudFromDepthImage | ( | const Image & | depth, |
| const camera::PinholeCameraIntrinsic & | intrinsic, | ||
| const Eigen::Matrix4d & | extrinsic = Eigen::Matrix4d::Identity(), |
||
| double | depth_scale = 1000.0, |
||
| double | depth_trunc = 1000.0, |
||
| int | stride = 1 |
||
| ) |
Factory function to create a pointcloud from a depth image and a camera model (PointCloudFactory.cpp) The input depth image can be either a float image, or a uint16_t image. In the latter case, the depth is scaled by 1 / depth_scale, and truncated at depth_trunc distance. The depth image is also sampled with stride, in order to support (fast) coarse point cloud extraction. Return an empty pointcloud if the conversion fails.
| std::shared_ptr< PointCloud > open3d::geometry::CreatePointCloudFromRGBDImage | ( | const RGBDImage & | image, |
| const camera::PinholeCameraIntrinsic & | intrinsic, | ||
| const Eigen::Matrix4d & | extrinsic = Eigen::Matrix4d::Identity() |
||
| ) |
Factory function to create a pointcloud from an RGB-D image and a camera model (PointCloudFactory.cpp) Return an empty pointcloud if the conversion fails.
| std::shared_ptr< RGBDImage > open3d::geometry::CreateRGBDImageFromColorAndDepth | ( | const Image & | color, |
| const Image & | depth, | ||
| double | depth_scale = 1000.0, |
||
| double | depth_trunc = 3.0, |
||
| bool | convert_rgb_to_intensity = true |
||
| ) |
Factory function to create an RGBD Image from color and depth Images.
| std::shared_ptr< RGBDImage > open3d::geometry::CreateRGBDImageFromNYUFormat | ( | const Image & | color, |
| const Image & | depth, | ||
| bool | convert_rgb_to_intensity = true |
||
| ) |
Factory function to create an RGBD Image from NYU dataset.
Reference: http://cs.nyu.edu/~silberman/datasets/nyu_depth_v2.html.
| std::shared_ptr< RGBDImage > open3d::geometry::CreateRGBDImageFromRedwoodFormat | ( | const Image & | color, |
| const Image & | depth, | ||
| bool | convert_rgb_to_intensity | ||
| ) |
Factory function to create an RGBD Image from Redwood dataset.
Reference: http://redwood-data.org/indoor/ File format: http://redwood-data.org/indoor/dataset.html
| std::shared_ptr< RGBDImage > open3d::geometry::CreateRGBDImageFromSUNFormat | ( | const Image & | color, |
| const Image & | depth, | ||
| bool | convert_rgb_to_intensity | ||
| ) |
Factory function to create an RGBD Image from SUN3D dataset.
Reference: http://sun3d.cs.princeton.edu/ File format: https://github.com/PrincetonVision/SUN3DCppReader
| std::shared_ptr< RGBDImage > open3d::geometry::CreateRGBDImageFromTUMFormat | ( | const Image & | color, |
| const Image & | depth, | ||
| bool | convert_rgb_to_intensity | ||
| ) |
Factory function to create an RGBD Image from TUM dataset.
Reference: http://vision.in.tum.de/data/datasets/rgbd-dataset File format: http://vision.in.tum.de/data/datasets/rgbd-dataset/file_formats
| RGBDImagePyramid open3d::geometry::CreateRGBDImagePyramid | ( | const RGBDImage & | rgbd_image, |
| size_t | num_of_levels, | ||
| bool | with_gaussian_filter_for_color, | ||
| bool | with_gaussian_filter_for_depth | ||
| ) |
| std::shared_ptr< VoxelGrid > open3d::geometry::CreateSurfaceVoxelGridFromPointCloud | ( | const PointCloud & | input, |
| double | voxel_size | ||
| ) |
| std::shared_ptr< PointCloud > open3d::geometry::CropPointCloud | ( | const PointCloud & | input, |
| const Eigen::Vector3d & | min_bound, | ||
| const Eigen::Vector3d & | max_bound | ||
| ) |
Function to crop
| input | pointcloud into output pointcloud All points with coordinates less than |
| min_bound | or larger than |
| max_bound | are clipped. |
| std::shared_ptr< TriangleMesh > open3d::geometry::CropTriangleMesh | ( | const TriangleMesh & | input, |
| const Eigen::Vector3d & | min_bound, | ||
| const Eigen::Vector3d & | max_bound | ||
| ) |
Function to crop
| input | tringlemesh into output tringlemesh All points with coordinates less than |
| min_bound | or larger than |
| max_bound | are clipped. |
| std::shared_ptr< Image > open3d::geometry::DilateImage | ( | const Image & | input, |
| int | half_kernel_size | ||
| ) |
Function to dilate 8bit mask map.
Function to 2x image downsample using simple 2x2 averaging.
| bool open3d::geometry::EstimateNormals | ( | PointCloud & | cloud, |
| const KDTreeSearchParam & | search_param = KDTreeSearchParamKNN() |
||
| ) |
Function to compute the normals of a point cloud
| cloud | is the input point cloud. It also stores the output normals. Normals are oriented with respect to the input point cloud if normals exist in the input. |
| search_param | The KDTree search parameters |
| std::shared_ptr< Image > open3d::geometry::FilterHorizontalImage | ( | const Image & | input, |
| const std::vector< double > & | kernel | ||
| ) |
| std::shared_ptr< Image > open3d::geometry::FilterImage | ( | const Image & | input, |
| Image::FilterType | type | ||
| ) |
Function to filter image with pre-defined filtering type.
| std::shared_ptr< Image > open3d::geometry::FilterImage | ( | const Image & | input, |
| const std::vector< double > & | dx, | ||
| const std::vector< double > & | dy | ||
| ) |
Function to filter image with arbitrary dx, dy separable filters.
| ImagePyramid open3d::geometry::FilterImagePyramid | ( | const ImagePyramid & | input, |
| Image::FilterType | type | ||
| ) |
Function to filter image pyramid.
| RGBDImagePyramid open3d::geometry::FilterRGBDImagePyramid | ( | const RGBDImagePyramid & | rgbd_image_pyramid, |
| Image::FilterType | type | ||
| ) |
| template int open3d::geometry::KDTreeFlann::Search< Eigen::Vector3d > | ( | const Eigen::Vector3d & | query, |
| const KDTreeSearchParam & | param, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| template int open3d::geometry::KDTreeFlann::Search< Eigen::VectorXd > | ( | const Eigen::VectorXd & | query, |
| const KDTreeSearchParam & | param, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| template int open3d::geometry::KDTreeFlann::SearchHybrid< Eigen::Vector3d > | ( | const Eigen::Vector3d & | query, |
| double | radius, | ||
| int | max_nn, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| template int open3d::geometry::KDTreeFlann::SearchHybrid< Eigen::VectorXd > | ( | const Eigen::VectorXd & | query, |
| double | radius, | ||
| int | max_nn, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| template int open3d::geometry::KDTreeFlann::SearchKNN< Eigen::Vector3d > | ( | const Eigen::Vector3d & | query, |
| int | knn, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| template int open3d::geometry::KDTreeFlann::SearchKNN< Eigen::VectorXd > | ( | const Eigen::VectorXd & | query, |
| int | knn, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| template int open3d::geometry::KDTreeFlann::SearchRadius< Eigen::Vector3d > | ( | const Eigen::Vector3d & | query, |
| double | radius, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| template int open3d::geometry::KDTreeFlann::SearchRadius< Eigen::VectorXd > | ( | const Eigen::VectorXd & | query, |
| double | radius, | ||
| std::vector< int > & | indices, | ||
| std::vector< double > & | distance2 | ||
| ) | const |
| void open3d::geometry::LinearTransformImage | ( | Image & | input, |
| double | scale = 1.0, |
||
| double | offset = 0.0 |
||
| ) |
Function to linearly transform pixel intensities image_new = scale * image + offset
| bool open3d::geometry::OrientNormalsToAlignWithDirection | ( | PointCloud & | cloud, |
| const Eigen::Vector3d & | orientation_reference = Eigen::Vector3d(0.0, 0.0, 1.0) |
||
| ) |
Function to orient the normals of a point cloud
| cloud | is the input point cloud. It must have normals. Normals are oriented with respect to |
| orientation_reference |
| bool open3d::geometry::OrientNormalsTowardsCameraLocation | ( | PointCloud & | cloud, |
| const Eigen::Vector3d & | camera_location = Eigen::Vector3d::Zero() |
||
| ) |
Function to orient the normals of a point cloud
| cloud | is the input point cloud. It also stores the output normals. Normals are oriented with towards |
| camera_location |
| T * open3d::geometry::PointerAt | ( | const Image & | image, |
| int | u, | ||
| int | v | ||
| ) |
Function to access the raw data of a single-channel Image.
| T * open3d::geometry::PointerAt | ( | const Image & | image, |
| int | u, | ||
| int | v, | ||
| int | ch | ||
| ) |
Function to access the raw data of a multi-channel Image.
| template float* open3d::geometry::PointerAt< float > | ( | const Image & | image, |
| int | u, | ||
| int | v | ||
| ) |
| template float* open3d::geometry::PointerAt< float > | ( | const Image & | image, |
| int | u, | ||
| int | v, | ||
| int | ch | ||
| ) |
| template int* open3d::geometry::PointerAt< int > | ( | const Image & | image, |
| int | u, | ||
| int | v | ||
| ) |
| template int* open3d::geometry::PointerAt< int > | ( | const Image & | image, |
| int | u, | ||
| int | v, | ||
| int | ch | ||
| ) |
| template uint16_t* open3d::geometry::PointerAt< uint16_t > | ( | const Image & | image, |
| int | u, | ||
| int | v | ||
| ) |
| template uint16_t* open3d::geometry::PointerAt< uint16_t > | ( | const Image & | image, |
| int | u, | ||
| int | v, | ||
| int | ch | ||
| ) |
| template uint8_t* open3d::geometry::PointerAt< uint8_t > | ( | const Image & | image, |
| int | u, | ||
| int | v | ||
| ) |
| template uint8_t* open3d::geometry::PointerAt< uint8_t > | ( | const Image & | image, |
| int | u, | ||
| int | v, | ||
| int | ch | ||
| ) |
| std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > open3d::geometry::RemoveRadiusOutliers | ( | const PointCloud & | input, |
| size_t | nb_points, | ||
| double | search_radius | ||
| ) |
Function to remove points that have less than
| nb_points | in a sphere of radius |
| search_radius |
| std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > open3d::geometry::RemoveStatisticalOutliers | ( | const PointCloud & | input, |
| size_t | nb_neighbors, | ||
| double | std_ratio | ||
| ) |
Function to remove points that are further away from their
| nb_neighbor | neighbors in average. |
| std::shared_ptr< PointCloud > open3d::geometry::SelectDownSample | ( | const PointCloud & | input, |
| const std::vector< size_t > & | indices, | ||
| bool | invert = false |
||
| ) |
Function to select points from
| input | pointcloud into |
| indices | are selected. |
| std::shared_ptr< TriangleMesh > open3d::geometry::SelectDownSample | ( | const TriangleMesh & | input, |
| const std::vector< size_t > & | indices | ||
| ) |
Function to select points from
| input | TriangleMesh into |
| indices | are selected. |
| std::shared_ptr< PointCloud > open3d::geometry::UniformDownSample | ( | const PointCloud & | input, |
| size_t | every_k_points | ||
| ) |
Function to downsample
| input | pointcloud into output pointcloud uniformly |
| every_k_points | indicates the sample rate. |
| std::shared_ptr< PointCloud > open3d::geometry::VoxelDownSample | ( | const PointCloud & | input, |
| double | voxel_size | ||
| ) |
Function to downsample
| input | pointcloud into output pointcloud with a voxel |
| voxel_size | defines the resolution of the voxel grid, smaller value leads to denser output point cloud. Normals and colors are averaged if they exist. |
| std::tuple< std::shared_ptr< PointCloud >, Eigen::MatrixXi > open3d::geometry::VoxelDownSampleAndTrace | ( | const PointCloud & | input, |
| double | voxel_size, | ||
| const Eigen::Vector3d & | min_bound, | ||
| const Eigen::Vector3d & | max_bound, | ||
| bool | approximate_class = false |
||
| ) |
Function to downsample using VoxelDownSample, but specialized for Surface convolution project. Experimental function.
1.8.13