tango_3d_reconstruction_api.h
Go to the documentation of this file.
1 // Copyright 2016 Google Inc. All Rights Reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 #ifndef TANGO_3D_RECONSTRUCTION_API_TANGO_3D_RECONSTRUCTION_API_H_
15 #define TANGO_3D_RECONSTRUCTION_API_TANGO_3D_RECONSTRUCTION_API_H_
16 
17 #include <stdbool.h>
18 #include <stdint.h>
19 
22 
23 #ifdef __cplusplus
24 extern "C" {
25 #endif
26 
30 
34 typedef enum {
44 
49 typedef enum {
55 
57 typedef enum {
75 
77 typedef enum {
83 
85 typedef enum {
91 
95 typedef enum {
108 
109 typedef enum {
115 
117 
121 
123 typedef struct _Tango3DR_ReconstructionContext* Tango3DR_ReconstructionContext;
124 
126 typedef struct _Tango3DR_TexturingContext* Tango3DR_TexturingContext;
127 
130 typedef struct _Tango3DR_Config* Tango3DR_Config;
131 
134 typedef struct _Tango3DR_Trajectory* Tango3DR_Trajectory;
135 
138 typedef struct _Tango3DR_AreaDescription* Tango3DR_AreaDescription;
139 
141 typedef float Tango3DR_Vector3[3];
142 
145 typedef float Tango3DR_Vector4[4];
146 
149 typedef uint32_t Tango3DR_Face[3];
150 
152 typedef uint8_t Tango3DR_Color[4];
153 
156 typedef int Tango3DR_GridIndex[3];
157 
159 typedef int Tango3DR_GridIndex2D[2];
160 
162 typedef float Tango3DR_TexCoord[2];
163 
172 
174  uint32_t width;
176  uint32_t height;
177 
179  double fx;
181  double fy;
183  double cx;
185  double cy;
186 
188  double distortion[5];
190 
194 typedef struct Tango3DR_Pose {
197  double translation[3];
198 
208  double orientation[4];
209 } Tango3DR_Pose;
210 
212 typedef struct Tango3DR_Matrix3x3 {
215  double data[9];
217 
221  int16_t sdf;
223  uint16_t weight;
225 
229 typedef struct Tango3DR_GridIndexArray {
231  uint32_t num_indices;
232 
234  Tango3DR_GridIndex* indices;
236 
240 typedef struct Tango3DR_PointCloud {
242  double timestamp;
243 
245  uint32_t num_points;
246 
250  Tango3DR_Vector4* points;
252 
257 typedef struct Tango3DR_ImageBuffer {
259  uint32_t width;
261  uint32_t height;
263  uint32_t stride;
265  double timestamp;
269  uint8_t* data;
271 
274 typedef struct Tango3DR_Mesh {
276  double timestamp;
277 
283  uint32_t num_vertices;
284 
286  uint32_t num_faces;
287 
289  uint32_t num_textures;
290 
297 
299  uint32_t max_num_faces;
300 
302  uint32_t max_num_textures; // Capacity of the texture array.
303 
305  Tango3DR_Vector3* vertices;
306 
308  Tango3DR_Face* faces;
309 
311  Tango3DR_Vector3* normals;
312 
314  Tango3DR_Color* colors;
315 
317  Tango3DR_TexCoord* texture_coords;
318 
320  int32_t* texture_ids;
321 
324 } Tango3DR_Mesh;
325 
327 typedef struct Tango3DR_FloorplanLevel {
329  float min_z;
330 
332  float max_z;
334 
338  uint32_t num_levels;
339 
343 
345 typedef float Tango3DR_Vector2[2];
346 
348 typedef enum {
354 
356 typedef struct Tango3DR_Polygon {
358  uint32_t num_vertices;
359 
362  bool closed;
363 
365  Tango3DR_FloorplanLayer layer;
366 
368  Tango3DR_Vector2* vertices; // In meters.
369 
372  double area; // In square meters.
374 
380 typedef struct Tango3DR_PolygonArray {
382  uint32_t num_polygons;
383 
387 
396 Tango3DR_Status Tango3DR_PointCloud_init(const uint32_t num_points,
397  Tango3DR_PointCloud* cloud);
398 
405 
413 
422  const char* const path);
423 
434 Tango3DR_Status Tango3DR_PointCloud_loadFromPly(const char* const path,
435  Tango3DR_PointCloud* cloud);
436 
443  Tango3DR_CameraCalibration* calibration);
444 
455  Tango3DR_CameraId camera_id, const char* const dataset_path,
456  Tango3DR_CameraCalibration* calibration);
457 
464 
475  Tango3DR_ImageBuffer* image);
476 
483 
493  const Tango3DR_ImageBuffer* image, const char* const path);
494 
506  const Tango3DR_ImageBuffer* image, const char* const path);
507 
520  Tango3DR_ImageBuffer* image);
521 
535  Tango3DR_ImageBuffer* image);
536 
543 
564  const uint32_t vertices_capacity, const uint32_t faces_capacity,
565  const bool allocate_normals, const bool allocate_colors,
566  const bool allocate_tex_coords, const bool allocate_tex_ids,
567  const uint32_t textures_capacity, const uint32_t textures_width,
568  const uint32_t textures_height, Tango3DR_Mesh* mesh);
569 
580 Tango3DR_Status Tango3DR_Mesh_loadFromObj(const char* const path,
581  Tango3DR_Mesh* mesh);
582 
592  const char* const path);
593 
600 
610  const uint32_t num_indices, Tango3DR_GridIndexArray* grid_index_array);
611 
618  Tango3DR_GridIndexArray* grid_index_array);
619 
628  Tango3DR_GridIndexArray* grid_index_array);
629 
631 //
635 //
639 //
648  const Tango3DR_PointCloud* cloud,
649  const Tango3DR_CameraCalibration* depth_camera_calibration,
650  Tango3DR_ImageBuffer* image);
651 
653 
792 
808 Tango3DR_Config Tango3DR_Config_create(Tango3DR_ConfigType config_type);
809 
814 Tango3DR_Status Tango3DR_Config_destroy(Tango3DR_Config config);
815 
824 Tango3DR_Status Tango3DR_Config_setBool(Tango3DR_Config config, const char* key,
825  bool value);
826 
835 Tango3DR_Status Tango3DR_Config_setInt32(Tango3DR_Config config,
836  const char* key, int32_t value);
837 
846 Tango3DR_Status Tango3DR_Config_setInt64(Tango3DR_Config config,
847  const char* key, int64_t value);
848 
857 Tango3DR_Status Tango3DR_Config_setDouble(Tango3DR_Config config,
858  const char* key, double value);
859 
868 Tango3DR_Status Tango3DR_Config_setMatrix3x3(Tango3DR_Config config,
869  const char* key,
870  const Tango3DR_Matrix3x3* value);
871 
880 Tango3DR_Status Tango3DR_Config_getBool(const Tango3DR_Config config,
881  const char* key, bool* value);
882 
891 Tango3DR_Status Tango3DR_Config_getInt32(const Tango3DR_Config config,
892  const char* key, int32_t* value);
893 
902 Tango3DR_Status Tango3DR_Config_getInt64(const Tango3DR_Config config,
903  const char* key, int64_t* value);
904 
913 Tango3DR_Status Tango3DR_Config_getDouble(const Tango3DR_Config config,
914  const char* key, double* value);
915 
924 Tango3DR_Status Tango3DR_Config_getMatrix3x3(Tango3DR_Config config,
925  const char* key,
926  Tango3DR_Matrix3x3* value);
927 
929 
959 
968 Tango3DR_ReconstructionContext Tango3DR_ReconstructionContext_create(
969  const Tango3DR_Config context_config);
970 
978  Tango3DR_ReconstructionContext context);
979 
987 Tango3DR_Status Tango3DR_clear(Tango3DR_ReconstructionContext context);
988 
1021  Tango3DR_ReconstructionContext context, const Tango3DR_PointCloud* cloud,
1022  const Tango3DR_Pose* cloud_pose, const Tango3DR_ImageBuffer* color_image,
1023  const Tango3DR_Pose* color_image_pose,
1024  Tango3DR_GridIndexArray* updated_indices);
1025 
1057  Tango3DR_ReconstructionContext context,
1058  const Tango3DR_ImageBuffer* depth_image,
1059  const Tango3DR_Pose* depth_image_pose,
1060  const Tango3DR_ImageBuffer* color_image,
1061  const Tango3DR_Pose* color_image_pose,
1062  Tango3DR_GridIndexArray* updated_indices);
1063 
1078  const Tango3DR_ReconstructionContext context,
1079  Tango3DR_GridIndexArray* active_indices);
1080 
1094  const Tango3DR_ReconstructionContext context,
1095  const Tango3DR_GridIndex grid_index, Tango3DR_Vector3* corner_min,
1096  Tango3DR_Vector3* corner_max);
1097 
1118  const Tango3DR_ReconstructionContext context,
1119  const Tango3DR_GridIndex grid_index, Tango3DR_Vector3* corner_min,
1120  Tango3DR_Vector3* corner_max);
1121 
1133  const Tango3DR_ReconstructionContext context,
1134  const Tango3DR_GridIndex grid_index, Tango3DR_Mesh* mesh);
1135 
1150  const Tango3DR_ReconstructionContext context,
1151  const Tango3DR_GridIndex grid_index, Tango3DR_Mesh* mesh);
1152 
1165  const Tango3DR_ReconstructionContext context,
1166  const Tango3DR_GridIndexArray* grid_index_array, Tango3DR_Mesh* mesh);
1167 
1183  const Tango3DR_ReconstructionContext context,
1184  const Tango3DR_GridIndexArray* grid_index_array, Tango3DR_Mesh* mesh);
1185 
1197  const Tango3DR_ReconstructionContext context, Tango3DR_Mesh* mesh);
1198 
1213  const Tango3DR_ReconstructionContext context, Tango3DR_Mesh* mesh);
1214 
1228  const Tango3DR_ReconstructionContext context,
1229  const Tango3DR_GridIndex grid_index, const int num_sdf_voxels,
1230  Tango3DR_SignedDistanceVoxel* sdf_voxels);
1231 
1242  const Tango3DR_ReconstructionContext context, const double min_plane_area,
1243  Tango3DR_Mesh* tango_mesh);
1244 
1255  const Tango3DR_ReconstructionContext context,
1256  const Tango3DR_CameraCalibration* calibration);
1257 
1267  const Tango3DR_ReconstructionContext context,
1268  const Tango3DR_CameraCalibration* calibration);
1269 
1281  const int new_width, const int new_height,
1282  Tango3DR_CameraCalibration* calibration_to_rescale);
1283 
1285 
1289 
1298 Tango3DR_TexturingContext Tango3DR_TexturingContext_create(
1299  const Tango3DR_Config texture_config, const Tango3DR_Mesh* tango_mesh);
1300 
1308  Tango3DR_TexturingContext context);
1309 
1319  const Tango3DR_TexturingContext context,
1320  const Tango3DR_CameraCalibration* calibration);
1321 
1332 Tango3DR_Status Tango3DR_updateTexture(Tango3DR_TexturingContext context,
1333  const Tango3DR_ImageBuffer* image,
1334  const Tango3DR_Pose* image_pose);
1335 
1349 Tango3DR_Status Tango3DR_updateTextureGl(Tango3DR_TexturingContext context,
1350  const int texture_target,
1351  const int image_texture_id,
1352  const Tango3DR_Pose* image_pose);
1353 
1363  const Tango3DR_TexturingContext context, Tango3DR_Mesh* tango_mesh_out);
1364 
1366 
1370 
1383  const Tango3DR_ReconstructionContext context,
1385 
1394  const Tango3DR_ReconstructionContext context);
1395 
1407  const Tango3DR_ReconstructionContext context,
1408  const Tango3DR_FloorplanLevel* level);
1409 
1414 
1424  const Tango3DR_ReconstructionContext context);
1425 
1436  const Tango3DR_ReconstructionContext context,
1437  const Tango3DR_GridIndexArray* grid_index_array);
1438 
1453  const Tango3DR_ReconstructionContext context,
1454  Tango3DR_PolygonArray* graphics);
1455 
1469  const Tango3DR_ReconstructionContext context,
1470  const Tango3DR_GridIndex2D grid_index, Tango3DR_PolygonArray* graphics);
1471 
1487  const Tango3DR_ReconstructionContext context, Tango3DR_FloorplanLayer layer,
1488  Tango3DR_Vector2* origin, Tango3DR_ImageBuffer* image);
1489 
1505  const Tango3DR_ReconstructionContext context,
1506  const Tango3DR_GridIndex2D grid_index, Tango3DR_FloorplanLayer layer,
1507  Tango3DR_ImageBuffer* image);
1508 
1513 
1515 
1526 
1534  Tango3DR_AreaDescription area_description);
1535 
1544  Tango3DR_AreaDescription area_description, const char* const path);
1545 
1556  const char* const path, Tango3DR_AreaDescription* area_description);
1557 
1565  const Tango3DR_AreaDescription area_description,
1566  Tango3DR_Trajectory* trajectory);
1567 
1574 Tango3DR_Status Tango3DR_Trajectory_destroy(Tango3DR_Trajectory trajectory);
1575 
1583  const Tango3DR_Trajectory trajectory, double* timestamp);
1584 
1592  const Tango3DR_Trajectory trajectory, double* timestamp);
1593 
1603 Tango3DR_Status Tango3DR_getPoseAtTime(const Tango3DR_Trajectory trajectory,
1604  const double timestamp,
1605  Tango3DR_Pose* tango_pose);
1606 
1608 
1612 
1614 typedef void (*Tango3DR_ProgressCallback)(int progress, void* callback_param);
1615 
1633  const char* dataset_path, const char* loop_closure_database_path,
1634  Tango3DR_AreaDescription* area_description,
1635  Tango3DR_ProgressCallback progress_callback, void* callback_param);
1636 
1651  const Tango3DR_ReconstructionContext context, const char* dataset_path,
1652  const Tango3DR_Trajectory trajectory,
1653  Tango3DR_ProgressCallback progress_callback, void* callback_param);
1654 
1676  const Tango3DR_Config texture_config, const char* dataset_path,
1677  const Tango3DR_Trajectory trajectory, const Tango3DR_Mesh* tango_mesh_in,
1678  Tango3DR_Mesh* tango_mesh_out, Tango3DR_ProgressCallback progress_callback,
1679  void* callback_param);
1680 
1681 // TODO(idryanov): Add link to documentation.
1693  const char* dataset_path, const char* output_path,
1694  Tango3DR_ProgressCallback progress_callback, void* callback_param);
1695 
1697 
1698 #ifdef __cplusplus
1699 }
1700 #endif
1701 
1702 #endif // TANGO_3D_RECONSTRUCTION_API_TANGO_3D_RECONSTRUCTION_API_H_
uint8_t * data
Pixels in the format of this image buffer.
Tango3DR_Status Tango3DR_extractPreallocatedVoxelGridSegment(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, const int num_sdf_voxels, Tango3DR_SignedDistanceVoxel *sdf_voxels)
struct _Tango3DR_Config * Tango3DR_Config
float Tango3DR_Vector4[4]
struct Tango3DR_FloorplanLevel Tango3DR_FloorplanLevel
Struct representing a single building level.
Tango3DR_Vector2 * vertices
2D points.
Tango3DR_Status Tango3DR_Trajectory_createFromAreaDescription(const Tango3DR_AreaDescription area_description, Tango3DR_Trajectory *trajectory)
Tango3DR_Status Tango3DR_CameraCalibration_loadFromDataset(Tango3DR_CameraId camera_id, const char *const dataset_path, Tango3DR_CameraCalibration *calibration)
Tango3DR_FloorplanLayer
Enumeration of floor plan layers.
Tango3DR_TexCoord * texture_coords
Texture coordinate buffer stored in UV order.
Tango3DR_Status Tango3DR_Trajectory_getEarliestTime(const Tango3DR_Trajectory trajectory, double *timestamp)
Tango3DR_Status Tango3DR_updateTextureGl(Tango3DR_TexturingContext context, const int texture_target, const int image_texture_id, const Tango3DR_Pose *image_pose)
Tango3DR_Status Tango3DR_extractPreallocatedMeshSegment(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_resetLevelsEstimator(const Tango3DR_ReconstructionContext context)
Tango3DR_Status Tango3DR_Config_setInt64(Tango3DR_Config config, const char *key, int64_t value)
void Tango3DR_destroyLevels(Tango3DR_FloorplanLevelArray *levels)
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)
This error code denotes some sort of hard error occurred.
Tango3DR_Status Tango3DR_ImageBuffer_saveToPng(const Tango3DR_ImageBuffer *image, const char *const path)
Tango3DR_Status Tango3DR_extractPreallocatedMesh(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndexArray *grid_index_array, Tango3DR_Mesh *mesh)
struct Tango3DR_Pose Tango3DR_Pose
uint32_t stride
The number of bytes per scanline of image data.
Back-facing fisheye wide-angle camera.
Tango3DR_Status Tango3DR_Mesh_saveToObj(const Tango3DR_Mesh *mesh, const char *const path)
struct Tango3DR_Mesh Tango3DR_Mesh
Tango3DR_Status Tango3DR_Config_getMatrix3x3(Tango3DR_Config config, const char *key, Tango3DR_Matrix3x3 *value)
Tango3DR_Status Tango3DR_Config_destroy(Tango3DR_Config config)
Tango3DR_Status Tango3DR_extractFullFloorplanImage(const Tango3DR_ReconstructionContext context, Tango3DR_FloorplanLayer layer, Tango3DR_Vector2 *origin, Tango3DR_ImageBuffer *image)
Tango3DR_Status
3D Reconstruction Error types. Errors less than 0 should be dealt with by the program. Success is denoted by TANGO_3DR_SUCCESS = 0.
Tango3DR_ImageBuffer * textures
Array of texture images.
Tango3DR_Status Tango3DR_GridIndexArray_initEmpty(Tango3DR_GridIndexArray *grid_index_array)
Tango3DR_Status Tango3DR_textureMeshFromDataset(const Tango3DR_Config texture_config, const char *dataset_path, const Tango3DR_Trajectory trajectory, const Tango3DR_Mesh *tango_mesh_in, Tango3DR_Mesh *tango_mesh_out, Tango3DR_ProgressCallback progress_callback, void *callback_param)
There is not enough space in a provided buffer.
struct Tango3DR_FloorplanLevelArray Tango3DR_FloorplanLevelArray
Struct representing building levels.
Tango3DR_Status Tango3DR_extractMeshSegment(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_CameraCalibration_rescale(const int new_width, const int new_height, Tango3DR_CameraCalibration *calibration_to_rescale)
Tango3DR_Status Tango3DR_TexturingContext_setColorCalibration(const Tango3DR_TexturingContext context, const Tango3DR_CameraCalibration *calibration)
Tango3DR_Status Tango3DR_Trajectory_destroy(Tango3DR_Trajectory trajectory)
Tango3DR_Status Tango3DR_ImageBuffer_loadFromPnm(const char *const path, Tango3DR_ImageBuffer *image)
struct Tango3DR_PolygonArray Tango3DR_PolygonArray
Struct representing a single building level.
Tango3DR_Status Tango3DR_AreaDescription_saveToAdf(Tango3DR_AreaDescription area_description, const char *const path)
The input argument is invalid.
Tango3DR_Status Tango3DR_GridIndexArray_destroy(Tango3DR_GridIndexArray *grid_index_array)
Tango3DR_Status Tango3DR_AreaDescription_destroy(Tango3DR_AreaDescription area_description)
uint16_t weight
Observation weight.
uint32_t num_indices
The number of indices in the indices field.
Tango3DR_Vector3 * normals
Normal buffer stored in XYZ order.
double distortion[5]
Distortion coefficients.
uint32_t num_points
The number of points in the points field.
uint32_t height
The height of the image data.
Tango3DR_FloorplanLevel * levels
Array with building level information.
uint32_t num_faces
Number of valid faces stored in the faces array.
Tango3DR_Status Tango3DR_ImageBuffer_initEmpty(Tango3DR_ImageBuffer *image)
double timestamp
Time of capture of the depth data for this struct (in seconds).
uint32_t width
The width of the image in pixels.
struct Tango3DR_Matrix3x3 Tango3DR_Matrix3x3
The Tango3DR_Matrix3x3 struct contains a single 3x3 matrix.
Tango3DR_Status Tango3DR_clear(Tango3DR_ReconstructionContext context)
Tango3DR_Status Tango3DR_extractFullMesh(const Tango3DR_ReconstructionContext context, Tango3DR_Mesh *mesh)
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.
Tango3DR_Status Tango3DR_Config_setInt32(Tango3DR_Config config, const char *key, int32_t value)
struct _Tango3DR_TexturingContext * Tango3DR_TexturingContext
This provides a handle to a Tango 3D texturing context.
struct _Tango3DR_Trajectory * Tango3DR_Trajectory
int Tango3DR_GridIndex2D[2]
An array of two integers describing a specific location in the 2D.
The Tango3DR_SignedDistanceVoxel struct contains a single voxel.
Tango3DR_Status Tango3DR_extractFullFloorplan(const Tango3DR_ReconstructionContext context, Tango3DR_PolygonArray *graphics)
Tango3DR_FloorplanLayer layer
Floor plan layer to which this path belongs to.
Tango3DR_Status Tango3DR_updateFloorplan(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndexArray *grid_index_array)
Tango3DR_ConfigType
Tango 3DR configuration enumerations.
Tango3DR_Status Tango3DR_updateFromTrajectoryAndDataset(const Tango3DR_ReconstructionContext context, const char *dataset_path, const Tango3DR_Trajectory trajectory, Tango3DR_ProgressCallback progress_callback, void *callback_param)
Tango3DR_Status Tango3DR_TexturingContext_destroy(Tango3DR_TexturingContext context)
float Tango3DR_Vector2[2]
An array of two floats, commonly a 2D position.
Tango3DR_Status Tango3DR_Config_getInt64(const Tango3DR_Config config, const char *key, int64_t *value)
Tango3DR_Status Tango3DR_updateFullFloorplan(const Tango3DR_ReconstructionContext context)
struct Tango3DR_SignedDistanceVoxel Tango3DR_SignedDistanceVoxel
The Tango3DR_SignedDistanceVoxel struct contains a single voxel.
Tango3DR_Color * colors
Color buffer stored in RGBA order.
Tango3DR_Status Tango3DR_AreaDescription_loadFromAdf(const char *const path, Tango3DR_AreaDescription *area_description)
Tango3DR_GridIndex * indices
Indices into a three-dimensional grid of cells.
float max_z
Vertical position of the ceiling (in meters).
Tango3DR_Status Tango3DR_extractLevels(const Tango3DR_ReconstructionContext context, Tango3DR_FloorplanLevelArray *levels)
Tango3DR_UpdateMethod
3D Reconstruction update algorithm types. Determines the algorithm used to update the reconstruction ...
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)
Tango3DR_Status Tango3DR_Config_setDouble(Tango3DR_Config config, const char *key, double value)
Default CPU texturing pipeline.
double timestamp
The timestamp of mesh generation (in seconds).
Tango3DR_Status Tango3DR_ReconstructionContext_setDepthCalibration(const Tango3DR_ReconstructionContext context, const Tango3DR_CameraCalibration *calibration)
Tango3DR_Status Tango3DR_extractRawDataFromDataset(const char *dataset_path, const char *output_path, Tango3DR_ProgressCallback progress_callback, void *callback_param)
Tango3DR_Vector3 * vertices
Vertex buffer stored in XYZ order.
void Tango3DR_VectorGraphics_destroy(Tango3DR_PolygonArray *graphics)
Tango3DR_Status Tango3DR_GridIndexArray_init(const uint32_t num_indices, Tango3DR_GridIndexArray *grid_index_array)
uint32_t max_num_faces
Maximum capacity of the faces array.
This code indicates success.
Tango3DR_Status Tango3DR_Mesh_loadFromObj(const char *const path, Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_ReconstructionContext_setColorCalibration(const Tango3DR_ReconstructionContext context, const Tango3DR_CameraCalibration *calibration)
Tango3DR_Status Tango3DR_Mesh_destroy(Tango3DR_Mesh *mesh)
Tango3DR_TexturingContext Tango3DR_TexturingContext_create(const Tango3DR_Config texture_config, const Tango3DR_Mesh *tango_mesh)
Tango3DR_Status Tango3DR_ImageBuffer_saveToPnm(const Tango3DR_ImageBuffer *image, const char *const path)
uint32_t max_num_textures
Maximum capacity of the textures
Tango3DR_Face * faces
Index buffer stored as a triangle list of 32 bit integers.
Tango3DR_TexturingBackend
Enumerates the available texturing backends.
float min_z
Vertical position of the floor (in meters).
OpenGL texturing pipeline, trading some quality for performance.
Tango3DR_Status Tango3DR_ImageBuffer_init(uint32_t width, uint32_t height, Tango3DR_ImageFormatType format, Tango3DR_ImageBuffer *image)
Struct representing building levels.
uint32_t num_vertices
Number of vertices contained in the vertices array.
double timestamp
The timestamp of this image.
Tango3DR_Status Tango3DR_extractFloorplanImageSegment(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex2D grid_index, Tango3DR_FloorplanLayer layer, Tango3DR_ImageBuffer *image)
Tango3DR_Status Tango3DR_getPoseAtTime(const Tango3DR_Trajectory trajectory, const double timestamp, Tango3DR_Pose *tango_pose)
Texturing configuration for Tango3DR_textureMeshFromDataset.
Tango3DR_Status Tango3DR_PointCloud_loadFromPly(const char *const path, Tango3DR_PointCloud *cloud)
Tango3DR_Status Tango3DR_Config_setMatrix3x3(Tango3DR_Config config, const char *key, const Tango3DR_Matrix3x3 *value)
uint32_t Tango3DR_Face[3]
Tango3DR_Status Tango3DR_PointCloud_init(const uint32_t num_points, Tango3DR_PointCloud *cloud)
Tango3DR_Status Tango3DR_extractMesh(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndexArray *grid_index_array, Tango3DR_Mesh *mesh)
struct Tango3DR_ImageBuffer Tango3DR_ImageBuffer
Tango3DR_Status Tango3DR_Trajectory_getLatestTime(const Tango3DR_Trajectory trajectory, double *timestamp)
Tango3DR_Status Tango3DR_getTexturedMesh(const Tango3DR_TexturingContext context, Tango3DR_Mesh *tango_mesh_out)
struct Tango3DR_Polygon Tango3DR_Polygon
Struct representing a single 2D polyline or polygon.
Tango3DR_Status Tango3DR_extractFloorplanSegment(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex2D grid_index, Tango3DR_PolygonArray *graphics)
Tango3DR_Status Tango3DR_ReconstructionContext_destroy(Tango3DR_ReconstructionContext context)
double fy
Focal length, y axis, in pixels.
Tango3DR_Status Tango3DR_PointCloud_saveToPly(const Tango3DR_PointCloud *cloud, const char *const path)
Tango3DR_Polygon * polygons
Array containing 2D polylines/polygons.
Tango3DR_Status Tango3DR_getMeshSegmentBoundingBox(const Tango3DR_ReconstructionContext context, const Tango3DR_GridIndex grid_index, Tango3DR_Vector3 *corner_min, Tango3DR_Vector3 *corner_max)
Tango3DR_Status Tango3DR_AreaDescription_createFromDataset(const char *dataset_path, const char *loop_closure_database_path, Tango3DR_AreaDescription *area_description, Tango3DR_ProgressCallback progress_callback, void *callback_param)
Tango3DR_ImageFormatType format
Pixel format of data.
Back-facing color camera.
uint32_t num_textures
Number of valid textures stored in the textures array.
struct Tango3DR_PointCloud Tango3DR_PointCloud
double cy
Principal point y coordinate on the image, in pixels.
uint32_t width
The width of the image data.
Tango3DR_Config Tango3DR_Config_create(Tango3DR_ConfigType config_type)
float Tango3DR_TexCoord[2]
An array of two floats describing a texture coordinate in UV order.
double fx
Focal length, x axis, in pixels.
Tango3DR_Status Tango3DR_ImageBuffer_destroy(Tango3DR_ImageBuffer *image)
float Tango3DR_Vector3[3]
An array of three floats, commonly a 3D position or normal.
struct _Tango3DR_AreaDescription * Tango3DR_AreaDescription
Tango3DR_Status Tango3DR_PointCloud_destroy(Tango3DR_PointCloud *cloud)
Back-facing infrared camera.
uint32_t height
The height of the image in pixels.
Tango3DR_Status Tango3DR_PointCloud_initEmpty(Tango3DR_PointCloud *cloud)
Tango3DR_TangoCalibrationType
Tango 3DR Camera Calibration types.
Tango3DR_Status Tango3DR_Config_getDouble(const Tango3DR_Config config, const char *key, double *value)
uint32_t num_polygons
Number of paths contained in the paths array.
Tango3DR_Status Tango3DR_extractPreallocatedFullMesh(const Tango3DR_ReconstructionContext context, Tango3DR_Mesh *mesh)
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_Config_setBool(Tango3DR_Config config, const char *key, bool value)
struct _Tango3DR_ReconstructionContext * Tango3DR_ReconstructionContext
This provides a handle to a Tango 3D reconstruction context.
struct Tango3DR_GridIndexArray Tango3DR_GridIndexArray
The Tango3DR_Matrix3x3 struct contains a single 3x3 matrix.
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_updateTexture(Tango3DR_TexturingContext context, const Tango3DR_ImageBuffer *image, const Tango3DR_Pose *image_pose)
Tango3DR_Status Tango3DR_Config_getInt32(const Tango3DR_Config config, const char *key, int32_t *value)
Struct representing a single 2D polyline or polygon.
Tango3DR_ReconstructionContext Tango3DR_ReconstructionContext_create(const Tango3DR_Config context_config)
void(* Tango3DR_ProgressCallback)(int progress, void *callback_param)
A callback function for dataset processing to report progress.
Tango3DR_Status Tango3DR_ReconstructionContext_decimatePlanes(const Tango3DR_ReconstructionContext context, const double min_plane_area, Tango3DR_Mesh *tango_mesh)
Tango3DR_TangoCalibrationType calibration_type
Back-facing depth camera.
struct Tango3DR_CameraCalibration Tango3DR_CameraCalibration
int Tango3DR_GridIndex[3]
Tango3DR_Status Tango3DR_selectLevel(const Tango3DR_ReconstructionContext context, const Tango3DR_FloorplanLevel *level)
int32_t * texture_ids
Mapping of faces to texture images. -1 means no texture assigned.
Tango3DR_Status Tango3DR_Config_getBool(const Tango3DR_Config config, const char *key, bool *value)
Tango3DR_Status Tango3DR_Mesh_initEmpty(Tango3DR_Mesh *mesh)
Tango3DR_Status Tango3DR_ImageBuffer_loadFromPng(const char *const path, Tango3DR_ImageBuffer *image)
double cx
Principal point x coordinate on the image, in pixels.
Tango3DR_Status Tango3DR_CameraCalibration_initEmpty(Tango3DR_CameraCalibration *calibration)
uint32_t num_levels
Number of building levels.
uint8_t Tango3DR_Color[4]
An array of four 8-bit integers describing a color in RGBA order.
int16_t sdf
Signed distance function, in normalized units.
Configuration for Tango3DR_ReconstructionContext_create.


tango_3d_reconstruction
Author(s):
autogenerated on Mon Jun 10 2019 15:37:45