cloudViewer.t.pipelines.slam.Model#
- class cloudViewer.t.pipelines.slam.Model#
Volumetric model for Dense SLAM.
- __init__(*args, **kwargs)#
Overloaded function.
- __init__(self, arg0)
Copy constructor
- Parameters:
arg0 (cloudViewer.t.pipelines.slam.Model) –
__init__(self)
- __init__(self, voxel_size, block_resolution=16, block_count: typing.SupportsInt = 10000, transformation=[[1 0 0 0], [0 1 0 0], [0 0 1 0], [0 0 0 1]] Tensor[shape={4, 4}, stride={4, 1}, Float64, , device=Device(“CUDA”, 0))
Constructor of a VoxelBlockGrid
- Parameters:
voxel_size (SupportsFloat) – The voxel size of the volume in meters.
(typing.SupportsInt (block_resolution) – typing.SupportsInt = 10000): Resolution of local dense voxel blocks. By default 16 is used to create 16^3 voxel blocks.
optional – typing.SupportsInt = 10000): Resolution of local dense voxel blocks. By default 16 is used to create 16^3 voxel blocks.
default=16 – typing.SupportsInt = 10000): Resolution of local dense voxel blocks. By default 16 is used to create 16^3 voxel blocks.
block_count – typing.SupportsInt = 10000): Resolution of local dense voxel blocks. By default 16 is used to create 16^3 voxel blocks.
transformation (cloudViewer.core.Tensor, optional, default=[[1 0 0 0], [0 1 0 0], [0 0 1 0], [0 0 0 1]] Tensor[shape={4, 4}, stride={4, 1}, Float64) – A 4x4 3D transformation matrix. ()
device (cloudViewer.core.Device, optional, default=Device("CUDA", 0)) – The CPU or CUDA device used for the object.
- extract_pointcloud(self, weight_threshold=3.0, estimated_number=-1)#
Extract point cloud from the volumetric model.
- Parameters:
weight_threshold (SupportsFloat, optional, default=3.0) – Weight threshold to filter outlier voxel blocks.
estimated_number (SupportsInt, optional, default=-1) – Estimated number of surface points. Use -1 if no estimation is available.
- Returns:
cloudViewer::t::geometry::PointCloud
- extract_trianglemesh(self, weight_threshold=3.0, estimated_number=-1)#
Extract triangle mesh from the volumetric model.
- Parameters:
weight_threshold (SupportsFloat, optional, default=3.0) – Weight threshold to filter outlier voxel blocks.
estimated_number (SupportsInt, optional, default=-1) – Estimated number of surface points. Use -1 if no estimation is available.
- Returns:
cloudViewer::t::geometry::TriangleMesh
- get_current_frame_pose(self: cloudViewer.t.pipelines.slam.Model) cloudViewer.core.Tensor#
- get_hashmap(self: cloudViewer.t.pipelines.slam.Model) cloudViewer.core.HashMap#
Get the underlying hash map from 3D coordinates to voxel blocks.
- integrate(self, input_frame, depth_scale=1000.0, depth_max=3.0, trunc_voxel_multiplier=8.0)#
Integrate an input frame to a volume.
- Parameters:
input_frame (cloudViewer::t::pipelines::slam::Frame) – The frame that contains raw depth and optionally images with the same size from the input.
depth_scale (SupportsFloat, optional, default=1000.0) – The scale factor to convert raw depth into meters.
depth_max (SupportsFloat, optional, default=3.0) – The max clipping depth to filter noisy observations too far.
trunc_voxel_multiplier (SupportsFloat, optional, default=8.0) – Truncation distance multiplier in voxel size for signed distance. For instance, –trunc_voxel_multiplier=8 with –voxel_size=0.006(m) creates a truncation distance of 0.048(m).
- Returns:
None
- synthesize_model_frame(self, model_frame, depth_scale=1000.0, depth_min=0.1, depth_max=3.0, trunc_voxel_multiplier=8.0, enable_color=False, weight_threshold=-1.0)#
Synthesize frame from the volumetric model using ray casting.
- Parameters:
model_frame (cloudViewer::t::pipelines::slam::Frame) – The frame that contains ray casted depth and optionally color from the volumetric model.
depth_scale (SupportsFloat, optional, default=1000.0) – The scale factor to convert raw depth into meters.
depth_min (SupportsFloat, optional, default=0.1) – The min clipping depth.
depth_max (SupportsFloat, optional, default=3.0) – The max clipping depth to filter noisy observations too far.
trunc_voxel_multiplier (SupportsFloat, optional, default=8.0) – Truncation distance multiplier in voxel size for signed distance. For instance, –trunc_voxel_multiplier=8 with –voxel_size=0.006(m) creates a truncation distance of 0.048(m).
enable_color (bool, optional, default=False) –
weight_threshold (SupportsFloat, optional, default=-1.0) – Weight threshold to filter outlier voxel blocks.
- Returns:
None
- track_frame_to_model(self, input_frame, model_frame, depth_scale=1000.0, depth_max=3.0, depth_diff=0.07, method=Method.PointToPlane, criteria=[OdometryConvergenceCriteria(max_iteration=6, relative_rmse=1.000000e-06, relative_fitness=1.000000e-06), OdometryConvergenceCriteria(max_iteration=3, relative_rmse=1.000000e-06, relative_fitness=1.000000e-06), OdometryConvergenceCriteria(max_iteration=1, relative_rmse=1.000000e-06, relative_fitness=1.000000e-06)])#
Track input frame against raycasted frame from model.
- Parameters:
input_frame (cloudViewer::t::pipelines::slam::Frame) – The frame that contains raw depth and optionally images with the same size from the input.
model_frame (cloudViewer::t::pipelines::slam::Frame) – The frame that contains ray casted depth and optionally color from the volumetric model.
depth_scale (SupportsFloat, optional, default=1000.0) – The scale factor to convert raw depth into meters.
depth_max (SupportsFloat, optional, default=3.0) – The max clipping depth to filter noisy observations too far.
depth_diff (SupportsFloat, optional, default=0.07) –
method (cloudViewer.t.pipelines.odometry.Method, optional, default=Method.PointToPlane) –
criteria (collections.abc.Sequence[cloudViewer.t.pipelines.odometry.OdometryConvergenceCriteria], optional, default=[OdometryConvergenceCriteria(max_iteration=6, relative_rmse=1.000000e-06, relative_fitness=1.000000e-06), OdometryConvergenceCriteria(max_iteration=3, relative_rmse=1.000000e-06, relative_fitness=1.000000e-06), OdometryConvergenceCriteria(max_iteration=1, relative_rmse=1.000000e-06, relative_fitness=1.000000e-06)]) –
- Returns:
cloudViewer.t.pipelines.odometry.OdometryResult
- update_frame_pose(self: cloudViewer.t.pipelines.slam.Model, arg0: SupportsInt, arg1: cloudViewer.core.Tensor) None#
- property frame_id#
Get the current frame index in a sequence.
- property frustum_block_coords#
Active block coordinates from prior integration
- property transformation_frame_to_world#
Get the 4x4 transformation matrix from the current frame to the world frame.
- property voxel_grid#
Get the maintained VoxelBlockGrid.