Classes | Typedefs | Enumerations | Functions | Variables
Tango 3D Reconstruction API types.

Tango 3D Reconstruction API types. More...

Classes

struct  Tango3DR_CameraCalibration
struct  Tango3DR_FloorplanLevel
 Struct representing a single building level. More...
struct  Tango3DR_FloorplanLevelArray
 Struct representing building levels. More...
struct  Tango3DR_GridIndexArray
struct  Tango3DR_ImageBuffer
struct  Tango3DR_Matrix3x3
 The Tango3DR_Matrix3x3 struct contains a single 3x3 matrix. More...
struct  Tango3DR_Mesh
struct  Tango3DR_PointCloud
struct  Tango3DR_Polygon
 Struct representing a single 2D polyline or polygon. More...
struct  Tango3DR_PolygonArray
struct  Tango3DR_Pose
struct  Tango3DR_SignedDistanceVoxel
 The Tango3DR_SignedDistanceVoxel struct contains a single voxel. More...

Typedefs

typedef struct
_Tango3DR_AreaDescription * 
Tango3DR_AreaDescription
typedef struct
Tango3DR_CameraCalibration 
Tango3DR_CameraCalibration
typedef uint8_t Tango3DR_Color [4]
 An array of four 8-bit integers describing a color in RGBA order.
typedef struct _Tango3DR_Config * Tango3DR_Config
typedef uint32_t Tango3DR_Face [3]
typedef struct
Tango3DR_FloorplanLevel 
Tango3DR_FloorplanLevel
 Struct representing a single building level.
typedef struct
Tango3DR_FloorplanLevelArray 
Tango3DR_FloorplanLevelArray
 Struct representing building levels.
typedef int Tango3DR_GridIndex [3]
typedef int Tango3DR_GridIndex2D [2]
 An array of two integers describing a specific location in the 2D.
typedef struct
Tango3DR_GridIndexArray 
Tango3DR_GridIndexArray
typedef struct Tango3DR_ImageBuffer Tango3DR_ImageBuffer
typedef struct Tango3DR_Matrix3x3 Tango3DR_Matrix3x3
 The Tango3DR_Matrix3x3 struct contains a single 3x3 matrix.
typedef struct Tango3DR_Mesh Tango3DR_Mesh
typedef struct Tango3DR_PointCloud Tango3DR_PointCloud
typedef struct Tango3DR_Polygon Tango3DR_Polygon
 Struct representing a single 2D polyline or polygon.
typedef struct
Tango3DR_PolygonArray 
Tango3DR_PolygonArray
typedef struct Tango3DR_Pose Tango3DR_Pose
typedef struct
_Tango3DR_ReconstructionContext * 
Tango3DR_ReconstructionContext
 This provides a handle to a Tango 3D reconstruction context.
typedef struct
Tango3DR_SignedDistanceVoxel 
Tango3DR_SignedDistanceVoxel
 The Tango3DR_SignedDistanceVoxel struct contains a single voxel.
typedef float Tango3DR_TexCoord [2]
 An array of two floats describing a texture coordinate in UV order.
typedef struct
_Tango3DR_TexturingContext * 
Tango3DR_TexturingContext
 This provides a handle to a Tango 3D texturing context.
typedef struct
_Tango3DR_Trajectory * 
Tango3DR_Trajectory
typedef float Tango3DR_Vector2 [2]
 An array of two floats, commonly a 2D position.
typedef float Tango3DR_Vector3 [3]
 An array of three floats, commonly a 3D position or normal.
typedef float Tango3DR_Vector4 [4]
typedef void * TangoAreaDescriptionMetadata
typedef void * TangoConfig
typedef struct
TangoCoordinateFrameId 
TangoCoordinateFrameId
typedef char TangoUUID [TANGO_UUID_LEN]

Enumerations

enum  Tango3DR_FloorplanLayer { TANGO_3DR_LAYER_SPACE = 0, TANGO_3DR_LAYER_WALLS, TANGO_3DR_LAYER_FURNITURE, TANGO_3DR_LAYER_OBSTACLES }
 Enumeration of floor plan layers. More...

Functions

Tango3DR_Status Tango3DR_CameraCalibration_initEmpty (Tango3DR_CameraCalibration *calibration)
Tango3DR_Status Tango3DR_CameraCalibration_loadFromDataset (Tango3DR_CameraId camera_id, const char *const dataset_path, Tango3DR_CameraCalibration *calibration)
Tango3DR_Status Tango3DR_GridIndexArray_destroy (Tango3DR_GridIndexArray *grid_index_array)
Tango3DR_Status Tango3DR_GridIndexArray_init (const uint32_t num_indices, Tango3DR_GridIndexArray *grid_index_array)
Tango3DR_Status Tango3DR_GridIndexArray_initEmpty (Tango3DR_GridIndexArray *grid_index_array)
Tango3DR_Status Tango3DR_ImageBuffer_destroy (Tango3DR_ImageBuffer *image)
Tango3DR_Status Tango3DR_ImageBuffer_init (uint32_t width, uint32_t height, Tango3DR_ImageFormatType format, Tango3DR_ImageBuffer *image)
Tango3DR_Status Tango3DR_ImageBuffer_initEmpty (Tango3DR_ImageBuffer *image)
Tango3DR_Status Tango3DR_ImageBuffer_loadFromPng (const char *const path, Tango3DR_ImageBuffer *image)
Tango3DR_Status Tango3DR_ImageBuffer_loadFromPnm (const char *const path, Tango3DR_ImageBuffer *image)
Tango3DR_Status Tango3DR_ImageBuffer_saveToPng (const Tango3DR_ImageBuffer *image, const char *const path)
Tango3DR_Status Tango3DR_ImageBuffer_saveToPnm (const Tango3DR_ImageBuffer *image, const char *const path)
Tango3DR_Status Tango3DR_Mesh_destroy (Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_Mesh_init (const uint32_t vertices_capacity, const uint32_t faces_capacity, const bool allocate_normals, const bool allocate_colors, const bool allocate_tex_coords, const bool allocate_tex_ids, const uint32_t textures_capacity, const uint32_t textures_width, const uint32_t textures_height, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_Mesh_initEmpty (Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_Mesh_loadFromObj (const char *const path, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_Mesh_saveToObj (const Tango3DR_Mesh *mesh, const char *const path)
Tango3DR_Status Tango3DR_PointCloud_destroy (Tango3DR_PointCloud *cloud)
Tango3DR_Status Tango3DR_PointCloud_init (const uint32_t num_points, Tango3DR_PointCloud *cloud)
Tango3DR_Status Tango3DR_PointCloud_initEmpty (Tango3DR_PointCloud *cloud)
Tango3DR_Status Tango3DR_PointCloud_loadFromPly (const char *const path, Tango3DR_PointCloud *cloud)
Tango3DR_Status Tango3DR_PointCloud_saveToPly (const Tango3DR_PointCloud *cloud, const char *const path)
Tango3DR_Status Tango3DR_PointCloudToRectifiedDepthImage (const Tango3DR_PointCloud *cloud, const Tango3DR_CameraCalibration *depth_camera_calibration, Tango3DR_ImageBuffer *image)
 Converts a point cloud into a depth image.

Variables

const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_AREA_DESCRIPTION
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_CAMERA_COLOR
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_CAMERA_DEPTH
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_CAMERA_FISHEYE
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_DEVICE
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_DISPLAY
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_GLOBAL_WGS84
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_IMU
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_NONE
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_PREVIOUS_DEVICE_POSE
const TangoCoordinateFrameId TANGO_COORDINATE_FRAME_ID_START_OF_SERVICE

Detailed Description

Tango 3D Reconstruction API types.


Typedef Documentation

typedef struct _Tango3DR_AreaDescription* Tango3DR_AreaDescription

This provides a handle to an area description, which further encodes the trajectory of the device.

Definition at line 138 of file tango_3d_reconstruction_api.h.

The Tango3DR_CameraCalibration struct contains intrinsic parameters for a camera.

The fields have the same meaning as in TangoCameraIntrinsics.

typedef uint8_t Tango3DR_Color[4]

An array of four 8-bit integers describing a color in RGBA order.

Definition at line 152 of file tango_3d_reconstruction_api.h.

typedef struct _Tango3DR_Config* Tango3DR_Config

This provides a handle to a Tango3DR_Config; key/value pairs can only be accessed through API calls.

Definition at line 130 of file tango_3d_reconstruction_api.h.

typedef uint32_t Tango3DR_Face[3]

An array of three 32-bit integers describing a single triangle in an index buffer.

Definition at line 149 of file tango_3d_reconstruction_api.h.

Struct representing a single building level.

Struct representing building levels.

typedef int Tango3DR_GridIndex[3]

An array of three integers describing a specific index in the 3D Reconstruction volume grid.

Definition at line 156 of file tango_3d_reconstruction_api.h.

typedef int Tango3DR_GridIndex2D[2]

An array of two integers describing a specific location in the 2D.

Definition at line 159 of file tango_3d_reconstruction_api.h.

The Tango3DR_GridIndexArray struct contains indices into a three-dimensional grid of cells. Each grid cell contains voxels arranged in a 16x16x16 cube.

The Tango3DR_ImageBuffer struct contains information about a byte buffer holding image data.

The image data is commonly copied from TangoImageBuffer.

The Tango3DR_Matrix3x3 struct contains a single 3x3 matrix.

typedef struct Tango3DR_Mesh Tango3DR_Mesh

A mesh, described by vertices and face indices, with optional per-vertex normals, colors, and textures.

The Tango3DR_PointCloud struct contains depth information.

The depth information is commonly copied from TangoXYZij.

Struct representing a single 2D polyline or polygon.

2D vector graphics object. The polygons are sorted by decreasing surface area, so that it is safe to render them directly using the provided ordering. Note that polygons with negative surface area indicate holes that need to be rendered in the background color.

typedef struct Tango3DR_Pose Tango3DR_Pose

The Tango3DR_Pose struct contains pose information.

The pose information is commonly copied from TangoPoseData.

typedef struct _Tango3DR_ReconstructionContext* Tango3DR_ReconstructionContext

This provides a handle to a Tango 3D reconstruction context.

Definition at line 123 of file tango_3d_reconstruction_api.h.

The Tango3DR_SignedDistanceVoxel struct contains a single voxel.

typedef float Tango3DR_TexCoord[2]

An array of two floats describing a texture coordinate in UV order.

Definition at line 162 of file tango_3d_reconstruction_api.h.

typedef struct _Tango3DR_TexturingContext* Tango3DR_TexturingContext

This provides a handle to a Tango 3D texturing context.

Definition at line 126 of file tango_3d_reconstruction_api.h.

typedef struct _Tango3DR_Trajectory* Tango3DR_Trajectory

This provides a handle to a trajectory, representing a path traveled over time.

Definition at line 134 of file tango_3d_reconstruction_api.h.

typedef float Tango3DR_Vector2[2]

An array of two floats, commonly a 2D position.

Definition at line 345 of file tango_3d_reconstruction_api.h.

typedef float Tango3DR_Vector3[3]

An array of three floats, commonly a 3D position or normal.

Definition at line 141 of file tango_3d_reconstruction_api.h.

typedef float Tango3DR_Vector4[4]

An array of four floats, commonly a point cloud point with confidence.

Definition at line 145 of file tango_3d_reconstruction_api.h.


Enumeration Type Documentation

Enumeration of floor plan layers.

Enumerator:
TANGO_3DR_LAYER_SPACE 
TANGO_3DR_LAYER_WALLS 
TANGO_3DR_LAYER_FURNITURE 
TANGO_3DR_LAYER_OBSTACLES 

Definition at line 348 of file tango_3d_reconstruction_api.h.


Function Documentation

Initialize an empty calibration struct.

Parameters:
calibrationPointer to camera calibration.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the struct. Returns TANGO_3DR_INVALID if calibration is NULL.
Tango3DR_Status Tango3DR_CameraCalibration_loadFromDataset ( Tango3DR_CameraId  camera_id,
const char *const  dataset_path,
Tango3DR_CameraCalibration calibration 
)

Load a camera calibration from a Tango dataset.

Parameters:
camera_idThe id of the camera. See Tango3DR_CameraId.
dataset_pathPath to the folder containing the Tango dataset.
calibrationThe calibration to be initialized.
Returns:
TANGO_3DR_SUCCESS on successful load. Returns TANGO_3DR_INVALID if on of the arguments is NULL, or if the provided camera_id is invalid. Returns@ TANGO_3DR_ERROR if the dataset cannot be found, or the calibration files in contains cannot be loaded.

Destroy a previously created grid index array.

Parameters:
grid_index_arrayPointer to a previously created grid index array.
Returns:
TANGO_3DR_SUCCESS on successfully destroying the grid index array. Returns TANGO_3DR_INVALID if grid_index_array is NULL.
Tango3DR_Status Tango3DR_GridIndexArray_init ( const uint32_t  num_indices,
Tango3DR_GridIndexArray grid_index_array 
)

Initialize a grid index array of a given size and allocate memory. Call Tango3DR_GridIndexArray_destroy to free the memory.

Parameters:
num_indicesHow many grid indices the newly allocated grid index array should be able to hold.
grid_index_arrayGrid index array to be initialized.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the array. Return TANGO_3DR_INVALID if array is NULL.

Initialize an empty grid index array.

Parameters:
grid_index_arrayGrid index array to be initialized.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the array. Return TANGO_3DR_INVALID if array is NULL.

Destroy a previously created image buffer.

Parameters:
imagePointer to a previously created image buffer.
Returns:
TANGO_3DR_SUCCESS on successfully destroying the image buffer. Returns TANGO_3DR_INVALID if image is NULL.
Tango3DR_Status Tango3DR_ImageBuffer_init ( uint32_t  width,
uint32_t  height,
Tango3DR_ImageFormatType  format,
Tango3DR_ImageBuffer image 
)

Initialize an image buffer of a given size and allocate memory. Call Tango3DR_ImageBuffer_destroy to free the memory.

Parameters:
widthImage width, in pixels.
heightImage height, in pixels.
formatImage format (see Tango3DR_ImageFormatType).
Returns:
TANGO_3DR_SUCCESS on successfully initializing the image. Return TANGO_3DR_INVALID if image is NULL.

Initialize an empty image buffer.

Parameters:
imageImage to be initialized.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the buffer. Returns TANGO_3DR_INVALID if image is NULL.
Tango3DR_Status Tango3DR_ImageBuffer_loadFromPng ( const char *const  path,
Tango3DR_ImageBuffer image 
)

Load an image from a .png file and allocate memory. Call Tango3DR_ImageBuffer_destroy to free the memory.

Parameters:
pathPath to the input PNG file.
cloudOn successful return, this will have memory allocated and filled out with the loaded image. The output image will be in either TANGO_3DR_HAL_PIXEL_FORMAT_RGBA_8888 or TANGO_3DR_HAL_PIXEL_FORMAT_RGB_888 format. After use, free this by calling Tango3DR_ImageBuffer_destroy.
Returns:
TANGO_3DR_SUCCESS on successfully loading the image, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if loading failed.
Tango3DR_Status Tango3DR_ImageBuffer_loadFromPnm ( const char *const  path,
Tango3DR_ImageBuffer image 
)

Load an image from a .pnm file and allocate memory. Call Tango3DR_ImageBuffer_destroy to free the memory.

Parameters:
pathPath to the input PNM file.
cloudOn successful return, this will have memory allocated and filled out with the loaded image. The output image will be in TANGO_3DR_HAL_PIXEL_FORMAT_DEPTH16 format. After use, free this by calling Tango3DR_ImageBuffer_destroy.
Returns:
TANGO_3DR_SUCCESS on successfully loading the image, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if loading failed.
Tango3DR_Status Tango3DR_ImageBuffer_saveToPng ( const Tango3DR_ImageBuffer image,
const char *const  path 
)

Save an image to a .png file. Only supports color images (in format TANGO_3DR_HAL_PIXEL_FORMAT_RGBA_8888, TANGO_3DR_HAL_PIXEL_FORMAT_RGB_888, or TANGO_3DR_HAL_PIXEL_FORMAT_YCrCb_420_SP).

Parameters:
imageImage to be written.
pathPath to output PNG image.
Returns:
TANGO_3DR_SUCCESS on successfully saving the image, TANGO_3DR_INVALID if the parameters are not valid or if the image format is invalid, TANGO_3DR_ERROR if saving failed.
Tango3DR_Status Tango3DR_ImageBuffer_saveToPnm ( const Tango3DR_ImageBuffer image,
const char *const  path 
)

Save an image to a .pnm file. Only supports depth images (in format TANGO_3DR_HAL_PIXEL_FORMAT_DEPTH16).

Parameters:
imageImage to be written.
pathPath to output PNM image.
Returns:
TANGO_3DR_SUCCESS on successfully saving the image, TANGO_3DR_INVALID if the parameters are not valid or if the image format is invalid, TANGO_3DR_ERROR if saving failed.

Destroy a previously created mesh.

Parameters:
meshPointer to a previously created mesh.
Returns:
TANGO_3DR_SUCCESS on successfully destroying the mesh. Returns TANGO_3DR_INVALID if mesh is NULL.
Tango3DR_Status Tango3DR_Mesh_init ( const uint32_t  vertices_capacity,
const uint32_t  faces_capacity,
const bool  allocate_normals,
const bool  allocate_colors,
const bool  allocate_tex_coords,
const bool  allocate_tex_ids,
const uint32_t  textures_capacity,
const uint32_t  textures_width,
const uint32_t  textures_height,
Tango3DR_Mesh mesh 
)

Initialize a mesh of a given size and allocate memory. Call Tango3DR_Mesh_destroy to free the memory.

Parameters:
vertices_capacityMaximum number of vertices this mesh can hold.
faces_capacityMaximum number of faces this mesh can hold.
allocate_normalsIf the normal buffer should be allocated.
allocate_colorsIf the color buffer should be allocated.
allocate_tex_coordsIf the texture coordinate buffer should be allocated.
textures_capacityMaximum number of textures this mesh can hold.
textures_widthWidth in pixels of the texture image buffers allocated.
textures_heightHeight in pixels of the texture image buffers allocated.
meshMesh to be initialized.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the mesh. Return TANGO_3DR_INVALID if mesh is NULL.

Initialize an empty mesh.

Parameters:
meshMesh to be initialized.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the mesh. Return TANGO_3DR_INVALID if mesh is NULL.
Tango3DR_Status Tango3DR_Mesh_loadFromObj ( const char *const  path,
Tango3DR_Mesh mesh 
)

Load a mesh from a .obj file and allocate memory. Call Tango3DR_Mesh_destroy to free the memory.

Parameters:
pathPath to the .obj mesh.
meshOn successful return, this will have memory allocated and filled out with the loaded mesh. After use, free this by calling Tango3DR_Mesh_destroy.
Returns:
TANGO_3DR_SUCCESS on successfully loading a mesh, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if loading failed.
Tango3DR_Status Tango3DR_Mesh_saveToObj ( const Tango3DR_Mesh mesh,
const char *const  path 
)

Save a mesh to an .obj file.

Parameters:
meshMesh to be saved.
pathOn successful return, this file will contain the mesh in OBJ format.
Returns:
TANGO_3DR_SUCCESS on successfully saving a mesh, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if saving failed.

Destroy a previously created point cloud.

Parameters:
cloudPointer to a previously created cloud.
Returns:
TANGO_3DR_SUCCESS on successfully destroying the point cloud. Returns TANGO_3DR_INVALID if cloud is NULL.
Tango3DR_Status Tango3DR_PointCloud_init ( const uint32_t  num_points,
Tango3DR_PointCloud cloud 
)

Initialize a point cloud of a given size and allocate memory. Call Tango3DR_PointCloud_destroy to free the memory.

Parameters:
num_pointsHow many points the newly allocated point cloud should have.
cloudPoint cloud to be initialized.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the cloud. Returns TANGO_3DR_INVALID if cloud is NULL.

Initialize an empty point cloud.

Parameters:
cloudPoint cloud to be initialized.
Returns:
TANGO_3DR_SUCCESS on successfully initializing the cloud. Returns TANGO_3DR_INVALID if cloud is NULL.
Tango3DR_Status Tango3DR_PointCloud_loadFromPly ( const char *const  path,
Tango3DR_PointCloud cloud 
)

Load a point cloud from a .ply file and allocate memory. Call Tango3DR_PointCloud_destroy to free the memory.

Parameters:
pathPath to the .ply file.
cloudOn successful return, this will have memory allocated and filled out with the loaded point cloud. After use, free this by calling Tango3DR_PointCloud_destroy.
Returns:
TANGO_3DR_SUCCESS on successfully loading the point cloud, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if loading failed.
Tango3DR_Status Tango3DR_PointCloud_saveToPly ( const Tango3DR_PointCloud cloud,
const char *const  path 
)

Save a point cloud to a .ply file.

Parameters:
meshPoint cloud to be written.
pathPath to output PLY file.
Returns:
TANGO_3DR_SUCCESS on successfully saving the point cloud, TANGO_3DR_INVALID if the parameters are not valid, TANGO_3DR_ERROR if saving failed.

Converts a point cloud into a depth image.

The input point cloud is assumed to be metrically correct. No additional image rectification is performed. The output depth image can thus be considered rectified. The output image must be pre-allocated before calling this function, with dimensions that match the width and height, and a format of TANGO_3DR_HAL_PIXEL_FORMAT_DEPTH16.

Parameters:
cloudthe input point cloud
depth_camera_calibrationcalibration containing camera parameters used for conversion. The distortion coefficients are not used.
imagePointer to preallocated image.
Returns:
@ TANGO_3DR_SUCCESS on successfully converting to depth image, @ TANGO_3DR_INVALID if the image is not allocated with the correct dimensions or format.


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