gradslam.structures¶
gradslam.structures.pointclouds¶
- class Pointclouds(points: Optional[Union[List[torch.Tensor], torch.Tensor]] = None, normals: Optional[Union[List[torch.Tensor], torch.Tensor]] = None, colors: Optional[Union[List[torch.Tensor], torch.Tensor]] = None, features: Optional[Union[List[torch.Tensor], torch.Tensor]] = None, device: Optional[Union[torch.device, str]] = None)[source]¶
Batch of pointclouds (with varying numbers of points), enabling conversion between 2 representations:
List: Store points of each pointcloud of shape \((N_b, 3)\) in a list of length \(B\).
Padded: Store all points in a \((B, max(N_b), 3)\) tensor with zero padding as required.
- Parameters
points (torch.Tensor or list of torch.Tensor or None) – \((X, Y, Z)\) coordinates of each point. Default: None
normals (torch.Tensor or list of torch.Tensor or None) – Normals \((N_x, N_y, N_z)\) of each point. Default: None
colors (torch.Tensor or list of torch.Tensor or None) – \((R, G, B)\) color of each point. Default: None
features (torch.Tensor or list of torch.Tensor or None) – \(C\) features of each point. Default: None
device (torch.device or str or None) – The desired device of internal tensors. If None, sets device to be same as points device. Default: None
- Shape:
points: Can either be a list of tensors of shape \((N_b, 3)\) or a padded tensor of shape \((B, N, 3)\).
normals: Can either be a list of tensors of shape \((N_b, 3)\) or a padded tensor of shape \((B, N, 3)\).
colors: Can either be a list of tensors of shape \((N_b, 3)\) or a padded tensor of shape \((B, N, 3)\).
features: Can either be a list of tensors of shape \((N_b, C)\) or a padded tensor of shape \((B, N, C)\).
Examples:
>>> points_list = [torch.rand(1, 3), torch.rand(4, 3)] >>> pcs1 = gradslam.Pointclouds(points_list) >>> print(pcs1.points_padded.shape) torch.Size([2, 4, 3]) >>> print(len(pcs1.points_list)) 2 >>> pcs2 = gradslam.Pointclouds(torch.rand((2, 4, 3))) >>> print(pcs2.points_padded.shape) torch.Size([2, 4, 3])
- append_points(pointclouds: gradslam.structures.pointclouds.Pointclouds)[source]¶
Appends points, normals, colors and features of a gradslam.Pointclouds object to the current pointclouds. Both Pointclouds must have/not have the same attributes. In place operation.
- Parameters
pointclouds (gradslam.Pointclouds) – Pointclouds to get appended to self. Must have same batch size as self.
- Returns
self
- clone()[source]¶
Returns deep copy of Pointclouds object. All internal tensors are cloned individually.
- Returns
cloned gradslam.Pointclouds object
- Return type
gradslam.Pointclouds
- property colors_list¶
Gets the list representation of the point colors.
- Returns
list of \(B\) tensors of colors of shape \((N_b, 3)\).
- Return type
list of torch.Tensor
- property colors_padded¶
Gets the padded representation of the colors.
- Returns
tensor representation of colors with zero padding as required
- Return type
- Shape:
Output: \((B, max(N_b), 3)\)
- detach()[source]¶
Detachs Pointclouds object. All internal tensors are detached individually.
- Returns
detached gradslam.Pointclouds object
- Return type
gradslam.Pointclouds
- property features_list¶
Gets the list representation of the point features.
- Returns
list of \(B\) tensors of features of shape \((N_b, 3)\).
- Return type
list of torch.Tensor
- property features_padded¶
Gets the padded representation of the features.
- Returns
tensor representation of features with zero padding as required
- Return type
- Shape:
Output: \((B, max(N_b), C)\)
- property has_colors¶
Determines whether pointclouds have colors or not
- Returns
bool
- property has_features¶
Determines whether pointclouds have features or not
- Returns
bool
- property has_normals¶
Determines whether pointclouds have normals or not
- Returns
bool
- property has_points¶
Determines whether pointclouds have points or not
- Returns
bool
- property nonpad_mask¶
Returns tensor of bool values which are True wherever points exist and False wherever there is padding.
- Returns
2d bool mask
- Return type
- Shape:
Output: \((B, N)\)
- property normals_list¶
Gets the list representation of the point normals.
- Returns
list of \(B\) tensors of normals of shape \((N_b, 3)\).
- Return type
list of torch.Tensor
- property normals_padded¶
Gets the padded representation of the normals.
- Returns
tensor representation of normals with zero padding as required
- Return type
- Shape:
Output: \((B, max(N_b), 3)\)
- property num_features¶
Determines number of features in pointclouds
- Returns
int
- property num_points_per_pointcloud¶
Returns a 1D tensor with length equal to the number of pointclouds giving the number of points in each pointcloud.
- Returns
1D tensor of sizes
- Return type
- Shape:
Output: tensor of shape \((B)\).
- offset_(offset: Union[torch.Tensor, float, int])[source]¶
Adds \(offset\) to all Pointclouds’ points. In place operation.
- Parameters
offset (torch.Tensor or float or int) – Value(s) to add to all points.
- Returns
self
- Shape:
offset: Any. Must be compatible with \((B, N, 3)\).
- open3d(index: int, include_colors: bool = True, max_num_points: Optional[int] = None, include_normals: bool = False)[source]¶
Converts index-th pointcloud to a open3d.geometry.Pointcloud object (e.g. for visualization).
- Parameters
index (int) – Index of which pointcloud (from the batch of pointclouds) to convert to open3d.geometry.Pointcloud.
include_colors (bool) – If True, will include colors in the o3d.geometry.Pointcloud objects. Default: True
max_num_points (int) – Maximum number of points to include in the returned object. If None, will not set a max size (will not downsample). Default: None
include_normals (bool) – If True, will include normal vectors in the o3d.geometry.Pointcloud objects. Default: False
- Returns
open3d.geometry.Pointcloud object from index-th pointcloud.
- Return type
pcd (open3d.geometry.Pointcloud)
- pinhole_projection(intrinsics: torch.Tensor)[source]¶
Out-of-place implementation of Pointclouds.pinhole_projection_
- pinhole_projection_(intrinsics: torch.Tensor)[source]¶
Projects Pointclouds’ points onto \(z=1\) plane using intrinsics of a pinhole camera. In place operation.
- Parameters
intrinsics (torch.Tensor) – Either batch or single intrinsics matrix
- Returns
self
- Shape:
intrinsics: \((4, 4)\) or \((B, 4, 4)\)
- plotly(index: int, include_colors: bool = True, max_num_points: Optional[int] = 200000, as_figure: bool = True, point_size: int = 2)[source]¶
Converts index-th pointcloud to either a plotly.graph_objects.Figure or a plotly.graph_objects.Scatter3d object (for visualization).
- Parameters
index (int) – Index of which pointcloud (from the batch of pointclouds) to convert to plotly representation.
include_colors (bool) – If True, will include point colors in the returned object. Default: True
max_num_points (int) – Maximum number of points to include in the returned object. If None, will not set a max size (will not downsample). Default: 200000
as_figure (bool) – If True, returns a plotly.graph_objects.Figure object which can easily be visualized by calling .show() on. Otherwise, returns a plotly.graph_objects.Scatter3d object. Default: True
point_size (int) – Point size radius (for visualization). Default: 2
- Returns
If as_figure is True, will return plotly.graph_objects.Figure object from the index-th pointcloud. Else, returns plotly.graph_objects.Scatter3d object from the index-th pointcloud.
- Return type
plotly.graph_objects.Figure or plotly.graph_objects.Scatter3d
- property points_list¶
Gets the list representation of the points.
- Returns
list of \(B\) tensors of points of shape \((N_b, 3)\).
- Return type
list of torch.Tensor
- property points_padded¶
Gets the padded representation of the points.
- Returns
tensor representation of points with zero padding as required
- Return type
- Shape:
Output: \((B, max(N_b), 3)\)
- rotate(rmat: torch.Tensor, *, pre_multiplication=True)[source]¶
Out-of-place implementation of Pointclouds.rotate_
- rotate_(rmat: torch.Tensor, *, pre_multiplication=True)[source]¶
Applies batch or single \(SO(3)\) rotation to all Pointclouds’ points and normals. In place operation.
- Parameters
rmat (torch.Tensor) – Either batch or single \(SO(3)\) rotation matrix
pre_multiplication (torch.Tensor) – If True, will pre-multiply the rotation. Otherwise will post-multiply the rotation. Default: True
- Returns
self
- Shape:
rmat: \((3, 3)\) or \((B, 3, 3)\)
- scale_(scale: Union[torch.Tensor, float, int])[source]¶
Scales all Pointclouds’ points by scale. In place operation.
- Parameters
scale (torch.Tensor or float or int) – Value(s) to scale all points by.
- Returns
self
- Shape:
scale: Any. Must be compatible with \((B, N, 3)\).
- to(device: Union[torch.device, str], copy: bool = False)[source]¶
Match functionality of torch.Tensor.to(device) If copy = True or the self Tensor is on a different device, the returned tensor is a copy of self with the desired torch.device. If copy = False and the self Tensor already has the correct torch.device, then self is returned.
- transform(transform: torch.Tensor, *, pre_multiplication=True)[source]¶
Out-of-place implementation of Pointclouds.transform_
- transform_(transform: torch.Tensor, *, pre_multiplication=True)[source]¶
Applies batch or single \(SE(3)\) transformation to all Pointclouds’ points and normals. In place operation.
- Parameters
transform (torch.Tensor) – Either batch or single \(SE(3)\) transformation tensor
pre_multiplication (torch.Tensor) – If True, will pre-multiply the transformation. Otherwise will post-multiply the transformation. Default: True
- Returns
self
- Shape:
transform: \((4, 4)\) or \((B, 4, 4)\)
gradslam.structures.rgbdimages¶
- class RGBDImages(rgb_image: torch.Tensor, depth_image: torch.Tensor, intrinsics: torch.Tensor, poses: Optional[torch.Tensor] = None, channels_first: bool = False, device: Optional[Union[torch.device, str]] = None, *, pixel_pos: Optional[torch.Tensor] = None)[source]¶
Initializes an RGBDImage object consisting of a batch of a sequence of rgb images, depth maps, camera intrinsics, and (optionally) poses.
- Parameters
rgb_image (torch.Tensor) – 3-channel rgb image
depth_image (torch.Tensor) – 1-channel depth map
intrinsics (torch.Tensor) – camera intrinsics
poses (torch.Tensor or None) – camera extrinsics. Default: None
channels_first (bool) – indicates whether rgb_image and depth_image have channels first or channels last representation (i.e. rgb_image.shape is \((B, L, H, W, 3)\) or \((B, L, 3, H, W)\). Default: False
device (torch.device or str or None) – The desired device of internal tensors. If None, sets device to be same as rgb_image device. Default: None
pixel_pos (torch.Tensor or None) – Similar to meshgrid but with extra channel of 1s at the end. If provided, can save computations when computing vertex maps. Default: None
- Shape:
rgb_image: \((B, L, H, W, 3)\) if channels_first is False, else \((B, L, 3, H, W)\)
depth_image: \((B, L, H, W, 1)\) if channels_first is False, else \((B, L, 1, H, W)\)
intrinsics: \((B, 1, 4, 4)\)
poses: \((B, L, 4, 4)\)
pixel_pos: \((B, L, H, W, 3)\) if channels_first is False, else \((B, L, 3, H, W)\)
Examples:
>>> colors = torch.rand([2, 8, 32, 32, 3]) >>> depths = torch.rand([2, 8, 32, 32, 1]) >>> intrinsics = torch.rand([2, 1, 4, 4]) >>> poses = torch.rand([2, 8, 4, 4]) >>> rgbdimages = gradslam.RGBDImages(colors, depths, intrinsics, poses) >>> print(rgbdimages.shape) (2, 8, 32, 32) >>> rgbd_select = rgbd_frame[1, 4:8] >>> print(rgbd_select.shape) (1, 4, 32, 32) >>> print(rgbdimages.vertex_map.shape) (2, 8, 32, 32, 3) >>> print(rgbdimages.normal_map.shape) (2, 8, 32, 32, 3)
- property cdim¶
Gets the channel dimension
- Returns
\(2\) if self.channels_first is True, else \(4\).
- Return type
- property channels_first¶
Gets bool indicating whether RGBDImages representation is channels first or not
- Returns
True if RGBDImages representation is channels first, else False.
- Return type
- clone()[source]¶
Returns deep copy of RGBDImages object. All internal tensors are cloned individually.
- Returns
cloned gradslam.RGBDImages object
- Return type
gradslam.RGBDImages
- property depth_image¶
Gets the depth image
- Returns
tensor representation of depth_image
- Return type
- Shape:
Output: \((B, L, H, W, 1)\) if self.channels_first is False, else \((B, L, 1, H, W)\)
- detach()[source]¶
Detachs RGBDImages object. All internal tensors are detached individually.
- Returns
detached gradslam.RGBDImages object
- Return type
gradslam.RGBDImages
- property global_normal_map¶
Gets the global normal maps
- Returns
tensor representation of global coordinated normal maps
- Return type
- Shape:
Output: \((B, L, H, W, 3)\) if self.channels_first is False, else \((B, L, 3, H, W)\)
- property global_vertex_map¶
Gets the global vertex maps
- Returns
tensor representation of global coordinated vertex maps
- Return type
- Shape:
Output: \((B, L, H, W, 3)\) if self.channels_first is False, else \((B, L, 3, H, W)\)
- property has_poses¶
Determines whether self has poses or not
- Returns
bool
- property intrinsics¶
Gets the intrinsics
- Returns
tensor representation of intrinsics
- Return type
- Shape:
Output: \((B, 1, 4, 4)\)
- property normal_map¶
Gets the local normal maps
- Returns
tensor representation of local coordinated normal maps
- Return type
- Shape:
Output: \((B, L, H, W, 3)\) if self.channels_first is False, else \((B, L, 3, H, W)\)
- property pixel_pos¶
Gets the pixel_pos
- Returns
tensor representation of pixel_pos
- Return type
- Shape:
Output: \((B, L, H, W, 3)\) if self.channels_first is False, else \((B, L, 3, H, W)\)
- plotly(index: int, include_depth: bool = True, as_figure: bool = True, ms_per_frame: int = 50)[source]¶
Converts index-th sequence of rgbd images to either a plotly.graph_objects.Figure or a list of dicts containing plotly.graph_objects.Image objects of rgb and (optionally) depth images:
frames = [ {'name': 0, 'data': [rgbImage0, depthImage0], 'traces': [0, 1]}, {'name': 1, 'data': [rgbImage1, depthImage1], 'traces': [0, 1]}, {'name': 2, 'data': [rgbImage2, depthImage2], 'traces': [0, 1]}, ... ]
Returned frames can be passed to go.Figure(frames=frames).
- Parameters
index (int) – Index of which rgbd image (from the batch of rgbd images) to convert to plotly representation.
include_depth (bool) – If True, will include depth images in the returned object. Default: True
as_figure (bool) – If True, returns a plotly.graph_objects.Figure object which can easily be visualized by calling .show() on. Otherwise, returns a list of dicts (frames) which can be passed to go.Figure(frames=frames). Default: True
ms_per_frame (int) – Milliseconds per frame when play button is hit. Only applicable if as_figure=True. Default: 50
- Returns
If as_figure is True, will return plotly.graph_objects.Figure object from the index-th sequence of rgbd images. Else, returns a list of dicts (frames).
- Return type
plotly.graph_objects.Figure or list of dict
- property poses¶
Gets the poses
- Returns
tensor representation of poses
- Return type
- Shape:
Output: \((B, L, 4, 4)\)
- property rgb_image¶
Gets the rgb image
- Returns
tensor representation of rgb_image
- Return type
- Shape:
Output: \((B, L, H, W, 3)\) if self.channels_first is False, else \((B, L, 3, H, W)\)
- to(device: Union[torch.device, str], copy: bool = False)[source]¶
Match functionality of torch.Tensor.to(device) If copy = True or the self Tensor is on a different device, the returned tensor is a copy of self with the desired torch.device. If copy = False and the self Tensor already has the correct torch.device, then self is returned.
- to_channels_first(copy: bool = False)[source]¶
Converts to channels first representation If copy = True or self channels_first is False, the returned RGBDImages object is a copy of self with channels first representation. If copy = False and self channels_first is already True, then self is returned.
- Parameters
copy (bool) – Boolean indicator whether or not to clone self. Default False.
- Returns
gradslam.RGBDImages
- to_channels_first_()[source]¶
Converts to channels first representation. In place operation.
- Returns
gradslam.RGBDImages
- to_channels_last(copy: bool = False)[source]¶
Converts to channels last representation If copy = True or self channels_first is True, the returned RGBDImages object is a copy of self with channels last representation. If copy = False and self channels_first is already False, then self is returned.
- Parameters
copy (bool) – Boolean indicator whether or not to clone self. Default False.
- Returns
gradslam.RGBDImages
- to_channels_last_()[source]¶
Converts to channels last representation. In place operation.
- Returns
gradslam.RGBDImages
- property valid_depth_mask¶
Gets a mask which is True wherever self.dept_image is \(>0\)
- Returns
Tensor of dtype bool with same shape as self.depth_image. Tensor is True wherever self.depth_image > 0, and False otherwise.
- Return type
- Shape:
Output: \((B, L, H, W, 1)\) if self.channels_first is False, else \((B, L, 1, H, W)\)
- property vertex_map¶
Gets the local vertex maps
- Returns
tensor representation of local coordinated vertex maps
- Return type
- Shape:
Output: \((B, L, H, W, 3)\) if self.channels_first is False, else \((B, L, 3, H, W)\)
gradslam.structures.utils¶
- pointclouds_from_rgbdimages(rgbdimages: gradslam.structures.rgbdimages.RGBDImages, *, global_coordinates: bool = True, filter_missing_depths: bool = True) → gradslam.structures.pointclouds.Pointclouds[source]¶
Converts gradslam.RGBDImages containing batch of RGB-D images with sequence length of 1 to gradslam.Pointclouds
- Parameters
rgbdimages (gradslam.RGBDImages) – Can contain a batch of RGB-D images but must have sequence length of 1.
global_coordinates (bool) – If True, will create pointclouds object based on \((X, Y, Z)\) coordinates in the global coordinates (based on rgbdimages.poses). Otherwise, will use the local frame coordinates.
filter_missing_depths (bool) – If True, will not include vertices corresponding to missing depth values in the output pointclouds.
- Returns
Output pointclouds
- Return type
gradslam.Pointclouds