Functions
Reconstruction

APIs for reconstruction of 3D meshes. More...

Functions

Tango3DR_Status Tango3DR_CameraCalibration_rescale (const int new_width, const int new_height, Tango3DR_CameraCalibration *calibration_to_rescale)
Tango3DR_Status Tango3DR_clear (Tango3DR_ReconstructionContext context)
Tango3DR_Status Tango3DR_extractFullMesh (const Tango3DR_ReconstructionContext context, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_extractMesh (const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndexArray *grid_index_array, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_extractMeshSegment (const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_extractPreallocatedFullMesh (const Tango3DR_ReconstructionContext context, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_extractPreallocatedMesh (const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndexArray *grid_index_array, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_extractPreallocatedMeshSegment (const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_extractPreallocatedVoxelGridSegment (const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, const int num_sdf_voxels, Tango3DR_SignedDistanceVoxel *sdf_voxels)
Tango3DR_Status Tango3DR_getActiveIndices (const Tango3DR_ReconstructionContext context, Tango3DR_GridIndexArray *active_indices)
Tango3DR_Status Tango3DR_getGridSegmentBoundingBox (const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, Tango3DR_Vector3 *corner_min, Tango3DR_Vector3 *corner_max)
Tango3DR_Status Tango3DR_getMeshSegmentBoundingBox (const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, Tango3DR_Vector3 *corner_min, Tango3DR_Vector3 *corner_max)
Tango3DR_ReconstructionContext Tango3DR_ReconstructionContext_create (const Tango3DR_Config context_config)
Tango3DR_Status Tango3DR_ReconstructionContext_decimatePlanes (const Tango3DR_ReconstructionContext context, const double min_plane_area, Tango3DR_Mesh *tango_mesh)
Tango3DR_Status Tango3DR_ReconstructionContext_destroy (Tango3DR_ReconstructionContext context)
Tango3DR_Status Tango3DR_ReconstructionContext_setColorCalibration (const Tango3DR_ReconstructionContext context, const Tango3DR_CameraCalibration *calibration)
Tango3DR_Status Tango3DR_ReconstructionContext_setDepthCalibration (const Tango3DR_ReconstructionContext context, const Tango3DR_CameraCalibration *calibration)
Tango3DR_Status Tango3DR_updateFromDepthImage (Tango3DR_ReconstructionContext context, const Tango3DR_ImageBuffer *depth_image, const Tango3DR_Pose *depth_image_pose, const Tango3DR_ImageBuffer *color_image, const Tango3DR_Pose *color_image_pose, Tango3DR_GridIndexArray *updated_indices)
Tango3DR_Status Tango3DR_updateFromPointCloud (Tango3DR_ReconstructionContext context, const Tango3DR_PointCloud *cloud, const Tango3DR_Pose *cloud_pose, const Tango3DR_ImageBuffer *color_image, const Tango3DR_Pose *color_image_pose, Tango3DR_GridIndexArray *updated_indices)

Detailed Description

APIs for reconstruction of 3D meshes.

To build a mesh on a Tango device in realtime with the API, follow the following steps:


Function Documentation

Tango3DR_Status Tango3DR_CameraCalibration_rescale ( const int  new_width,
const int  new_height,
Tango3DR_CameraCalibration calibration_to_rescale 
)

Rescales the camera calibration given a new width and height. This function adapts the camera calibration parameters for scaled images. This is useful for camera images that are downsampled before being used in Tango3DR_updateFromDepthImage / Tango3DR_updateTexture.

Parameters:
new_widthThe new width.
new_heightThe new height.
calibration_to_rescaleThe rescaled camera calibration.
Returns:
TANGO_3DR_SUCCESS on success, if the parameters are not valid.

Clear all voxels from a running context.

Parameters:
contextHandle to a previously created context.
Returns:
TANGO_3DR_SUCCESS on successfully clearing the context's voxels. Returns TANGO_3DR_INVALID if context is NULL.

Extract a single mesh for the current state of all active grid cells.

Parameters:
contextHandle to a previously created context.
meshOn successful return, a freshly allocated Tango3DR_Mesh containing the mesh for all active grid cells. After use, free this by calling Tango3DR_Mesh_destroy().
Returns:
TANGO_3DR_SUCCESS on success, TANGO_3DR_INVALID if the parameters are not valid, and TANGO_3DR_ERROR if some other error occurred.

Extract a single mesh for the current state of multiple grid cells.

Parameters:
contextHandle to a previously created context.
grid_index_arrayArray of grid cells to extract.
meshOn successful return, a freshly allocated Tango3DR_Mesh containing the mesh for the grid cells. After use, free this by calling Tango3DR_Mesh_destroy().
Returns:
TANGO_3DR_SUCCESS on success, TANGO_3DR_INVALID if the parameters are not valid, and TANGO_3DR_ERROR if some other error occurred.

Extract a mesh for the current state of a grid cell.

Parameters:
contextHandle to a previously created context.
grid_indexIndex for the grid cell to extract.
meshOn successful return, a freshly allocated Tango3DR_Mesh containing the mesh for the grid cell. After use, free this by calling Tango3DR_Mesh_destroy().
Returns:
TANGO_3DR_SUCCESS on success, TANGO_3DR_INVALID if the parameters are not valid, and TANGO_3DR_ERROR if some other error occurred.

Extract a single mesh for the current state of all active grid cells.

Parameters:
contextHandle to a previously created context.
meshPointer to a previously allocated mesh. On successful return the buffers of the mesh will be updated to represent the mesh. When TANGO_3DR_INSUFFICIENT_SPACE is returned, as much of the mesh as possible will be filled in.
Returns:
TANGO_3DR_SUCCESS on success, TANGO_3DR_INSUFFICIENT_SPACE if extraction was successful but there was not enough space for all the buffers, TANGO_3DR_INVALID if the parameters are not valid, and TANGO_3DR_ERROR if some other error occurred.

Extract a single mesh for the current state of multiple grid cells.

Parameters:
contextHandle to a previously created context.
grid_index_arrayArray of grid cells to extract.
meshPointer to a previously allocated mesh. On successful return the buffers of the mesh will be updated to represent the mesh. When TANGO_3DR_INSUFFICIENT_SPACE is returned, as much of the mesh as possible will be filled in.
Returns:
TANGO_3DR_SUCCESS on success, TANGO_3DR_INSUFFICIENT_SPACE if extraction was successful but there was not enough space for all the buffers, TANGO_3DR_INVALID if the parameters are not valid, and TANGO_3DR_ERROR if some other error occurred.

Extract a mesh for the current state of a grid cell.

Parameters:
contextHandle to a previously created context.
grid_indexIndex for the grid cell to extract.
meshPointer to a previously allocated mesh. On successful return the buffers of the mesh will be updated to represent the mesh. When TANGO_3DR_INSUFFICIENT_SPACE is returned, as much of the mesh as possible will be filled in.
Returns:
TANGO_3DR_SUCCESS on success, TANGO_3DR_INSUFFICIENT_SPACE if extraction was successful but there was not enough space for all the buffers, TANGO_3DR_INVALID if the parameters are not valid, and TANGO_3DR_ERROR if some other error occurred.
Tango3DR_Status Tango3DR_extractPreallocatedVoxelGridSegment ( const Tango3DR_ReconstructionContext  context,
const Tango3DR_GridIndex  grid_index,
const int  num_sdf_voxels,
Tango3DR_SignedDistanceVoxel sdf_voxels 
)

Extract voxels for the current state of a grid cell.

Parameters:
contextHandle to a previously created context.
grid_indexIndex for the grid cell to extract.
num_sdf_voxelsNumber of voxels in this grid cell. Must be 16x16x16 = 4096.
sdf_voxelsPointer to a previously allocated list of voxels. On successful return sdf_voxels will be updated to represent the current state.
Returns:
TANGO_3DR_SUCCESS on success, TANGO_3DR_INVALID if the parameters are not valid, and TANGO_3DR_ERROR if some other error occurred.

Retrieves the indices of all active cells.

A cell is marked as active if it has any voxels that have been updated by Tango3DR_update and will remain active until reconstruction is cleared using Tango3DR_clear().

Parameters:
contextHandle to a previously created context.
updated_indicesOn successful return, this will be filled with a pointer to a freshly allocated Tango3DR_GridIndexArray containing all grid cells that are active. After use, free this by calling Tango3DR_GridIndexArray_destroy().
Returns:
TANGO_3DR_SUCCESS on success and TANGO_3DR_INVALID if the parameters are not valid.

Retrieves two position vectors that define the axis-aligned bounding box of a grid cell. Dimentions are in meters. Adjacent bounding boxes do not overlap and do not have space between them.

Parameters:
contextHandle to a previously created context.
grid_indexIndex of the grid segment.
corner_lowPosition of the bottom left near corner of the grid index in world coordinates.
corner_highPosition of the top right far corner of the grid index in world coordinates.
Returns:
TANGO_3DR_SUCCESS on success and TANGO_3DR_INVALID if the parameters are not valid.

Retrieves positions of two corners that define location and shape of a mesh segment. Dimentions are in meters. Note that this is not necessarily the minimum bounding box, but the upper bound of mesh segment vertex positions. Adjacent bounding boxes do not overlap and do not have space between them.

The bounding box of a mesh segment is not guaranteed to exactly overlap with the bounding box of the corresponding grid segment (see Tango3DR_getGridSegmentBoundingBox). A mesh segment's bounding box can extend slightly beyond the grid segment's bounding box, in order to guarantee seamless connection to the neighboring meshes.

Parameters:
contextHandle to a previously created context.
grid_indexIndex of the mesh segment.
corner_lowPosition of the bottom left near corner of the grid index in world coordinates.
corner_highPosition of the top right far corner of the grid index in world coordinates.
Returns:
TANGO_3DR_SUCCESS on success and TANGO_3DR_INVALID if the parameters are not valid.

Create a new Tango 3D Reconstruction context and return a handle to it. You can run as many 3D Reconstruction contexts as you want.

Parameters:
context_configThe context will be started with the setting specified by this config handle. If NULL is passed here, then the context will be started in the default configuration.
Returns:
A handle to the Tango 3D Reconstruction context.
Tango3DR_Status Tango3DR_ReconstructionContext_decimatePlanes ( const Tango3DR_ReconstructionContext  context,
const double  min_plane_area,
Tango3DR_Mesh tango_mesh 
)

Find planar regions in a mesh and decimates them separately from the rest of the mesh.

Parameters:
contextHandle to a reconstruction context.
min_plane_areaMinimum area of a flat surface to be simplified. In square meters.
tango_meshmesh that will be analyzed and decimated.
Returns:
TANGO_3DR_SUCCESS on success, if the parameters are not valid.

Destroy a previously created Tango 3D Reconstruction context.

Parameters:
contextHandle to a previously created context.
Returns:
TANGO_3DR_SUCCESS on successfully destroying the context. Returns TANGO_3DR_INVALID if context is NULL.

Sets the color camera intrinsic calibration that a reconstruction context uses. It is required to call this function once before calling Tango3DR_update if you are passing color images to the reconstruction.

Parameters:
contextHandle to a reconstruction context.
calibrationThe calibration parameters of the color camera.
Returns:
TANGO_3DR_SUCCESS on success, if the parameters are not valid.

Sets the depth camera intrinsic calibration that a reconstruction context uses. It is required to call this function once before calling Tango3DR_update if the update_method flag is set to TANGO_3DR_PROJECTIVE_UPDATE.

Parameters:
contextHandle to a reconstruction context.
calibrationThe calibration parameters of the depth camera.
Returns:
TANGO_3DR_SUCCESS on success, if the parameters are not valid.
Tango3DR_Status Tango3DR_updateFromDepthImage ( Tango3DR_ReconstructionContext  context,
const Tango3DR_ImageBuffer depth_image,
const Tango3DR_Pose depth_image_pose,
const Tango3DR_ImageBuffer color_image,
const Tango3DR_Pose color_image_pose,
Tango3DR_GridIndexArray updated_indices 
)

Updates the reconstruction using a depth image and (optional) color image.

This is the preferred update method when using the TANGO_3DR_PROJECTIVE_UPDATE setting. When using the TANGO_3DR_TRAVERSAL_UPDATE, setting, this method will result in a implicit conversion to point cloud first. In such cases, consider using Tango3DR_updateFromPointCloud instead.

A list of affected grid cells are returned so that you can create new meshes for only those cells via the various mesh and floorplan extraction methods.

Parameters:
contextHandle to a previously created context.
depth_imageInput depth image.
depth_image_posePose of the depth camera at the time of capturing the depth_image.
color_imageImage data. Ideally, the image should be in TANGO_3DR_HAL_PIXEL_FORMAT_YCrCb_420_SP. Other formats (RGB/RGBA) will be converted automatically. If image is NULL, no color information will be generated for affected cells.
color_image_posePose of the color camera when capturing the data in color_image. Can be NULL if color_image is NULL.
updated_indicesOn successful return, this will be populated with the grid cells which were affected by the update. After use, free this by calling Tango3DR_GridIndexArray_destroy().
Returns:
TANGO_3DR_SUCCESS on successfully updating the reconstruction, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if Tango3DR_ReconstructionContext_setDepthCalibration method hasn't been called, and TANGO_3DR_ERROR if passing in a color image but the Tango3DR_ReconstructionContext_setColorCalibration method hasnt't been called.
Tango3DR_Status Tango3DR_updateFromPointCloud ( Tango3DR_ReconstructionContext  context,
const Tango3DR_PointCloud cloud,
const Tango3DR_Pose cloud_pose,
const Tango3DR_ImageBuffer color_image,
const Tango3DR_Pose color_image_pose,
Tango3DR_GridIndexArray updated_indices 
)

Updates the reconstruction using a point cloud and (optional) color image.

This is the preferred update method when using the TANGO_3DR_TRAVERSAL_UPDATE setting. When using the TANGO_3DR_PROJECTIVE_UPDATE, setting, this method will result in a implicit conversion to depth image first. In such cases, consider using Tango3DR_updateFromDepthImage instead.

A list of affected grid cells are returned so that you can create new meshes for only those cells via the various mesh and floorplan extraction methods.

Parameters:
contextHandle to a previously created context.
cloudInput point cloud.
cloud_posePose of the depth camera at the time of capturing the cloud.
color_imageImage data. Ideally, the image should be in TANGO_3DR_HAL_PIXEL_FORMAT_YCrCb_420_SP. Other formats (RGB/RGBA) will be converted automatically. If image is NULL, no color information will be generated for affected cells.
color_image_posePose of the color camera when capturing the data in color_image. Can be NULL if color_image is NULL.
updated_indicesOn successful return, this will be populated with the grid cells which were affected by the update. After use, free this by calling Tango3DR_GridIndexArray_destroy().
Returns:
TANGO_3DR_SUCCESS on successfully updating the reconstruction, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if using TANGO_3DR_PROJECTIVE_UPDATE but the Tango3DR_ReconstructionContext_setDepthCalibration method hasn't been called, and TANGO_3DR_ERROR if passing in a color image but the Tango3DR_ReconstructionContext_setColorCalibration method hasnt't been called.


tango_3d_reconstruction
Author(s):
autogenerated on Thu Jun 6 2019 19:49:50