tango_3d_reconstruction_api.h
Go to the documentation of this file.
00001 // Copyright 2016 Google Inc. All Rights Reserved.
00002 //
00003 // Licensed under the Apache License, Version 2.0 (the "License");
00004 // you may not use this file except in compliance with the License.
00005 // You may obtain a copy of the License at
00006 //
00007 //      http://www.apache.org/licenses/LICENSE-2.0
00008 //
00009 // Unless required by applicable law or agreed to in writing, software
00010 // distributed under the License is distributed on an "AS IS" BASIS,
00011 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00012 // See the License for the specific language governing permissions and
00013 // limitations under the License.
00014 #ifndef TANGO_3D_RECONSTRUCTION_API_TANGO_3D_RECONSTRUCTION_API_H_
00015 #define TANGO_3D_RECONSTRUCTION_API_TANGO_3D_RECONSTRUCTION_API_H_
00016 
00017 #include <stdbool.h>
00018 #include <stdint.h>
00019 
00022 
00023 #ifdef __cplusplus
00024 extern "C" {
00025 #endif
00026 
00030 
00034 typedef enum {
00036   TANGO_3DR_ERROR = -3,
00038   TANGO_3DR_INSUFFICIENT_SPACE = -2,
00040   TANGO_3DR_INVALID = -1,
00042   TANGO_3DR_SUCCESS = 0
00043 } Tango3DR_Status;
00044 
00049 typedef enum {
00050   TANGO_3DR_HAL_PIXEL_FORMAT_RGBA_8888 = 1,         
00051   TANGO_3DR_HAL_PIXEL_FORMAT_RGB_888 = 3,           
00052   TANGO_3DR_HAL_PIXEL_FORMAT_YCrCb_420_SP = 0x11,   
00053   TANGO_3DR_HAL_PIXEL_FORMAT_DEPTH16 = 0x44363159,  
00054 } Tango3DR_ImageFormatType;
00055 
00057 typedef enum {
00058   TANGO_3DR_CALIBRATION_UNKNOWN = 0,
00062   TANGO_3DR_CALIBRATION_EQUIDISTANT = 1,
00067   TANGO_3DR_CALIBRATION_POLYNOMIAL_2_PARAMETERS = 2,
00070   TANGO_3DR_CALIBRATION_POLYNOMIAL_3_PARAMETERS = 3,
00073   TANGO_3DR_CALIBRATION_POLYNOMIAL_5_PARAMETERS = 4,
00074 } Tango3DR_TangoCalibrationType;
00075 
00077 typedef enum {
00079   TANGO_3DR_CONFIG_RECONSTRUCTION = 0,
00081   TANGO_3DR_CONFIG_TEXTURING = 1
00082 } Tango3DR_ConfigType;
00083 
00085 typedef enum {
00087   TANGO_3DR_CPU_TEXTURING = 0,
00089   TANGO_3DR_GL_TEXTURING = 1,
00090 } Tango3DR_TexturingBackend;
00091 
00095 typedef enum {
00100   TANGO_3DR_TRAVERSAL_UPDATE = 0,
00106   TANGO_3DR_PROJECTIVE_UPDATE = 1,
00107 } Tango3DR_UpdateMethod;
00108 
00109 typedef enum {
00110   TANGO_3DR_CAMERA_COLOR = 0,    
00111   TANGO_3DR_CAMERA_IR = 1,       
00112   TANGO_3DR_CAMERA_FISHEYE = 2,  
00113   TANGO_3DR_CAMERA_DEPTH = 3,    
00114 } Tango3DR_CameraId;
00115 
00117 
00121 
00123 typedef struct _Tango3DR_ReconstructionContext* Tango3DR_ReconstructionContext;
00124 
00126 typedef struct _Tango3DR_TexturingContext* Tango3DR_TexturingContext;
00127 
00130 typedef struct _Tango3DR_Config* Tango3DR_Config;
00131 
00134 typedef struct _Tango3DR_Trajectory* Tango3DR_Trajectory;
00135 
00138 typedef struct _Tango3DR_AreaDescription* Tango3DR_AreaDescription;
00139 
00141 typedef float Tango3DR_Vector3[3];
00142 
00145 typedef float Tango3DR_Vector4[4];
00146 
00149 typedef uint32_t Tango3DR_Face[3];
00150 
00152 typedef uint8_t Tango3DR_Color[4];
00153 
00156 typedef int Tango3DR_GridIndex[3];
00157 
00159 typedef int Tango3DR_GridIndex2D[2];
00160 
00162 typedef float Tango3DR_TexCoord[2];
00163 
00168 typedef struct Tango3DR_CameraCalibration {
00171   Tango3DR_TangoCalibrationType calibration_type;
00172 
00174   uint32_t width;
00176   uint32_t height;
00177 
00179   double fx;
00181   double fy;
00183   double cx;
00185   double cy;
00186 
00188   double distortion[5];
00189 } Tango3DR_CameraCalibration;
00190 
00194 typedef struct Tango3DR_Pose {
00197   double translation[3];
00198 
00208   double orientation[4];
00209 } Tango3DR_Pose;
00210 
00212 typedef struct Tango3DR_Matrix3x3 {
00215   double data[9];
00216 } Tango3DR_Matrix3x3;
00217 
00219 typedef struct Tango3DR_SignedDistanceVoxel {
00221   int16_t sdf;
00223   uint16_t weight;
00224 } Tango3DR_SignedDistanceVoxel;
00225 
00229 typedef struct Tango3DR_GridIndexArray {
00231   uint32_t num_indices;
00232 
00234   Tango3DR_GridIndex* indices;
00235 } Tango3DR_GridIndexArray;
00236 
00240 typedef struct Tango3DR_PointCloud {
00242   double timestamp;
00243 
00245   uint32_t num_points;
00246 
00250   Tango3DR_Vector4* points;
00251 } Tango3DR_PointCloud;
00252 
00257 typedef struct Tango3DR_ImageBuffer {
00259   uint32_t width;
00261   uint32_t height;
00263   uint32_t stride;
00265   double timestamp;
00267   Tango3DR_ImageFormatType format;
00269   uint8_t* data;
00270 } Tango3DR_ImageBuffer;
00271 
00274 typedef struct Tango3DR_Mesh {
00276   double timestamp;
00277 
00283   uint32_t num_vertices;
00284 
00286   uint32_t num_faces;
00287 
00289   uint32_t num_textures;
00290 
00296   uint32_t max_num_vertices;
00297 
00299   uint32_t max_num_faces;
00300 
00302   uint32_t max_num_textures;  // Capacity of the texture array.
00303 
00305   Tango3DR_Vector3* vertices;
00306 
00308   Tango3DR_Face* faces;
00309 
00311   Tango3DR_Vector3* normals;
00312 
00314   Tango3DR_Color* colors;
00315 
00317   Tango3DR_TexCoord* texture_coords;
00318 
00320   int32_t* texture_ids;
00321 
00323   Tango3DR_ImageBuffer* textures;
00324 } Tango3DR_Mesh;
00325 
00327 typedef struct Tango3DR_FloorplanLevel {
00329   float min_z;
00330 
00332   float max_z;
00333 } Tango3DR_FloorplanLevel;
00334 
00336 typedef struct Tango3DR_FloorplanLevelArray {
00338   uint32_t num_levels;
00339 
00341   Tango3DR_FloorplanLevel* levels;
00342 } Tango3DR_FloorplanLevelArray;
00343 
00345 typedef float Tango3DR_Vector2[2];
00346 
00348 typedef enum {
00349   TANGO_3DR_LAYER_SPACE = 0,
00350   TANGO_3DR_LAYER_WALLS,
00351   TANGO_3DR_LAYER_FURNITURE,
00352   TANGO_3DR_LAYER_OBSTACLES
00353 } Tango3DR_FloorplanLayer;
00354 
00356 typedef struct Tango3DR_Polygon {
00358   uint32_t num_vertices;
00359 
00362   bool closed;
00363 
00365   Tango3DR_FloorplanLayer layer;
00366 
00368   Tango3DR_Vector2* vertices;  // In meters.
00369 
00372   double area;  // In square meters.
00373 } Tango3DR_Polygon;
00374 
00380 typedef struct Tango3DR_PolygonArray {
00382   uint32_t num_polygons;
00383 
00385   Tango3DR_Polygon* polygons;
00386 } Tango3DR_PolygonArray;
00387 
00396 Tango3DR_Status Tango3DR_PointCloud_init(const uint32_t num_points,
00397                                          Tango3DR_PointCloud* cloud);
00398 
00404 Tango3DR_Status Tango3DR_PointCloud_initEmpty(Tango3DR_PointCloud* cloud);
00405 
00412 Tango3DR_Status Tango3DR_PointCloud_destroy(Tango3DR_PointCloud* cloud);
00413 
00421 Tango3DR_Status Tango3DR_PointCloud_saveToPly(const Tango3DR_PointCloud* cloud,
00422                                               const char* const path);
00423 
00434 Tango3DR_Status Tango3DR_PointCloud_loadFromPly(const char* const path,
00435                                                 Tango3DR_PointCloud* cloud);
00436 
00442 Tango3DR_Status Tango3DR_CameraCalibration_initEmpty(
00443     Tango3DR_CameraCalibration* calibration);
00444 
00454 Tango3DR_Status Tango3DR_CameraCalibration_loadFromDataset(
00455     Tango3DR_CameraId camera_id, const char* const dataset_path,
00456     Tango3DR_CameraCalibration* calibration);
00457 
00463 Tango3DR_Status Tango3DR_ImageBuffer_initEmpty(Tango3DR_ImageBuffer* image);
00464 
00473 Tango3DR_Status Tango3DR_ImageBuffer_init(uint32_t width, uint32_t height,
00474                                           Tango3DR_ImageFormatType format,
00475                                           Tango3DR_ImageBuffer* image);
00476 
00482 Tango3DR_Status Tango3DR_ImageBuffer_destroy(Tango3DR_ImageBuffer* image);
00483 
00492 Tango3DR_Status Tango3DR_ImageBuffer_saveToPnm(
00493     const Tango3DR_ImageBuffer* image, const char* const path);
00494 
00505 Tango3DR_Status Tango3DR_ImageBuffer_saveToPng(
00506     const Tango3DR_ImageBuffer* image, const char* const path);
00507 
00519 Tango3DR_Status Tango3DR_ImageBuffer_loadFromPnm(const char* const path,
00520                                                  Tango3DR_ImageBuffer* image);
00521 
00534 Tango3DR_Status Tango3DR_ImageBuffer_loadFromPng(const char* const path,
00535                                                  Tango3DR_ImageBuffer* image);
00536 
00542 Tango3DR_Status Tango3DR_Mesh_initEmpty(Tango3DR_Mesh* mesh);
00543 
00563 Tango3DR_Status Tango3DR_Mesh_init(
00564     const uint32_t vertices_capacity, const uint32_t faces_capacity,
00565     const bool allocate_normals, const bool allocate_colors,
00566     const bool allocate_tex_coords, const bool allocate_tex_ids,
00567     const uint32_t textures_capacity, const uint32_t textures_width,
00568     const uint32_t textures_height, Tango3DR_Mesh* mesh);
00569 
00580 Tango3DR_Status Tango3DR_Mesh_loadFromObj(const char* const path,
00581                                           Tango3DR_Mesh* mesh);
00582 
00591 Tango3DR_Status Tango3DR_Mesh_saveToObj(const Tango3DR_Mesh* mesh,
00592                                         const char* const path);
00593 
00599 Tango3DR_Status Tango3DR_Mesh_destroy(Tango3DR_Mesh* mesh);
00600 
00609 Tango3DR_Status Tango3DR_GridIndexArray_init(
00610     const uint32_t num_indices, Tango3DR_GridIndexArray* grid_index_array);
00611 
00617 Tango3DR_Status Tango3DR_GridIndexArray_initEmpty(
00618     Tango3DR_GridIndexArray* grid_index_array);
00619 
00627 Tango3DR_Status Tango3DR_GridIndexArray_destroy(
00628     Tango3DR_GridIndexArray* grid_index_array);
00629 
00631 //
00635 //
00639 //
00647 Tango3DR_Status Tango3DR_PointCloudToRectifiedDepthImage(
00648     const Tango3DR_PointCloud* cloud,
00649     const Tango3DR_CameraCalibration* depth_camera_calibration,
00650     Tango3DR_ImageBuffer* image);
00651 
00653 
00792 
00808 Tango3DR_Config Tango3DR_Config_create(Tango3DR_ConfigType config_type);
00809 
00814 Tango3DR_Status Tango3DR_Config_destroy(Tango3DR_Config config);
00815 
00824 Tango3DR_Status Tango3DR_Config_setBool(Tango3DR_Config config, const char* key,
00825                                         bool value);
00826 
00835 Tango3DR_Status Tango3DR_Config_setInt32(Tango3DR_Config config,
00836                                          const char* key, int32_t value);
00837 
00846 Tango3DR_Status Tango3DR_Config_setInt64(Tango3DR_Config config,
00847                                          const char* key, int64_t value);
00848 
00857 Tango3DR_Status Tango3DR_Config_setDouble(Tango3DR_Config config,
00858                                           const char* key, double value);
00859 
00868 Tango3DR_Status Tango3DR_Config_setMatrix3x3(Tango3DR_Config config,
00869                                              const char* key,
00870                                              const Tango3DR_Matrix3x3* value);
00871 
00880 Tango3DR_Status Tango3DR_Config_getBool(const Tango3DR_Config config,
00881                                         const char* key, bool* value);
00882 
00891 Tango3DR_Status Tango3DR_Config_getInt32(const Tango3DR_Config config,
00892                                          const char* key, int32_t* value);
00893 
00902 Tango3DR_Status Tango3DR_Config_getInt64(const Tango3DR_Config config,
00903                                          const char* key, int64_t* value);
00904 
00913 Tango3DR_Status Tango3DR_Config_getDouble(const Tango3DR_Config config,
00914                                           const char* key, double* value);
00915 
00924 Tango3DR_Status Tango3DR_Config_getMatrix3x3(Tango3DR_Config config,
00925                                              const char* key,
00926                                              Tango3DR_Matrix3x3* value);
00927 
00929 
00959 
00968 Tango3DR_ReconstructionContext Tango3DR_ReconstructionContext_create(
00969     const Tango3DR_Config context_config);
00970 
00977 Tango3DR_Status Tango3DR_ReconstructionContext_destroy(
00978     Tango3DR_ReconstructionContext context);
00979 
00987 Tango3DR_Status Tango3DR_clear(Tango3DR_ReconstructionContext context);
00988 
01020 Tango3DR_Status Tango3DR_updateFromPointCloud(
01021     Tango3DR_ReconstructionContext context, const Tango3DR_PointCloud* cloud,
01022     const Tango3DR_Pose* cloud_pose, const Tango3DR_ImageBuffer* color_image,
01023     const Tango3DR_Pose* color_image_pose,
01024     Tango3DR_GridIndexArray* updated_indices);
01025 
01056 Tango3DR_Status Tango3DR_updateFromDepthImage(
01057     Tango3DR_ReconstructionContext context,
01058     const Tango3DR_ImageBuffer* depth_image,
01059     const Tango3DR_Pose* depth_image_pose,
01060     const Tango3DR_ImageBuffer* color_image,
01061     const Tango3DR_Pose* color_image_pose,
01062     Tango3DR_GridIndexArray* updated_indices);
01063 
01077 Tango3DR_Status Tango3DR_getActiveIndices(
01078     const Tango3DR_ReconstructionContext context,
01079     Tango3DR_GridIndexArray* active_indices);
01080 
01093 Tango3DR_Status Tango3DR_getGridSegmentBoundingBox(
01094     const Tango3DR_ReconstructionContext context,
01095     const Tango3DR_GridIndex grid_index, Tango3DR_Vector3* corner_min,
01096     Tango3DR_Vector3* corner_max);
01097 
01117 Tango3DR_Status Tango3DR_getMeshSegmentBoundingBox(
01118     const Tango3DR_ReconstructionContext context,
01119     const Tango3DR_GridIndex grid_index, Tango3DR_Vector3* corner_min,
01120     Tango3DR_Vector3* corner_max);
01121 
01132 Tango3DR_Status Tango3DR_extractMeshSegment(
01133     const Tango3DR_ReconstructionContext context,
01134     const Tango3DR_GridIndex grid_index, Tango3DR_Mesh* mesh);
01135 
01149 Tango3DR_Status Tango3DR_extractPreallocatedMeshSegment(
01150     const Tango3DR_ReconstructionContext context,
01151     const Tango3DR_GridIndex grid_index, Tango3DR_Mesh* mesh);
01152 
01164 Tango3DR_Status Tango3DR_extractMesh(
01165     const Tango3DR_ReconstructionContext context,
01166     const Tango3DR_GridIndexArray* grid_index_array, Tango3DR_Mesh* mesh);
01167 
01182 Tango3DR_Status Tango3DR_extractPreallocatedMesh(
01183     const Tango3DR_ReconstructionContext context,
01184     const Tango3DR_GridIndexArray* grid_index_array, Tango3DR_Mesh* mesh);
01185 
01196 Tango3DR_Status Tango3DR_extractFullMesh(
01197     const Tango3DR_ReconstructionContext context, Tango3DR_Mesh* mesh);
01198 
01212 Tango3DR_Status Tango3DR_extractPreallocatedFullMesh(
01213     const Tango3DR_ReconstructionContext context, Tango3DR_Mesh* mesh);
01214 
01227 Tango3DR_Status Tango3DR_extractPreallocatedVoxelGridSegment(
01228     const Tango3DR_ReconstructionContext context,
01229     const Tango3DR_GridIndex grid_index, const int num_sdf_voxels,
01230     Tango3DR_SignedDistanceVoxel* sdf_voxels);
01231 
01241 Tango3DR_Status Tango3DR_ReconstructionContext_decimatePlanes(
01242     const Tango3DR_ReconstructionContext context, const double min_plane_area,
01243     Tango3DR_Mesh* tango_mesh);
01244 
01254 Tango3DR_Status Tango3DR_ReconstructionContext_setDepthCalibration(
01255     const Tango3DR_ReconstructionContext context,
01256     const Tango3DR_CameraCalibration* calibration);
01257 
01266 Tango3DR_Status Tango3DR_ReconstructionContext_setColorCalibration(
01267     const Tango3DR_ReconstructionContext context,
01268     const Tango3DR_CameraCalibration* calibration);
01269 
01280 Tango3DR_Status Tango3DR_CameraCalibration_rescale(
01281     const int new_width, const int new_height,
01282     Tango3DR_CameraCalibration* calibration_to_rescale);
01283 
01285 
01289 
01298 Tango3DR_TexturingContext Tango3DR_TexturingContext_create(
01299     const Tango3DR_Config texture_config, const Tango3DR_Mesh* tango_mesh);
01300 
01307 Tango3DR_Status Tango3DR_TexturingContext_destroy(
01308     Tango3DR_TexturingContext context);
01309 
01318 Tango3DR_Status Tango3DR_TexturingContext_setColorCalibration(
01319     const Tango3DR_TexturingContext context,
01320     const Tango3DR_CameraCalibration* calibration);
01321 
01332 Tango3DR_Status Tango3DR_updateTexture(Tango3DR_TexturingContext context,
01333                                        const Tango3DR_ImageBuffer* image,
01334                                        const Tango3DR_Pose* image_pose);
01335 
01349 Tango3DR_Status Tango3DR_updateTextureGl(Tango3DR_TexturingContext context,
01350                                          const int texture_target,
01351                                          const int image_texture_id,
01352                                          const Tango3DR_Pose* image_pose);
01353 
01362 Tango3DR_Status Tango3DR_getTexturedMesh(
01363     const Tango3DR_TexturingContext context, Tango3DR_Mesh* tango_mesh_out);
01364 
01366 
01370 
01382 Tango3DR_Status Tango3DR_extractLevels(
01383     const Tango3DR_ReconstructionContext context,
01384     Tango3DR_FloorplanLevelArray* levels);
01385 
01393 Tango3DR_Status Tango3DR_resetLevelsEstimator(
01394     const Tango3DR_ReconstructionContext context);
01395 
01406 Tango3DR_Status Tango3DR_selectLevel(
01407     const Tango3DR_ReconstructionContext context,
01408     const Tango3DR_FloorplanLevel* level);
01409 
01413 void Tango3DR_destroyLevels(Tango3DR_FloorplanLevelArray* levels);
01414 
01423 Tango3DR_Status Tango3DR_updateFullFloorplan(
01424     const Tango3DR_ReconstructionContext context);
01425 
01435 Tango3DR_Status Tango3DR_updateFloorplan(
01436     const Tango3DR_ReconstructionContext context,
01437     const Tango3DR_GridIndexArray* grid_index_array);
01438 
01452 Tango3DR_Status Tango3DR_extractFullFloorplan(
01453     const Tango3DR_ReconstructionContext context,
01454     Tango3DR_PolygonArray* graphics);
01455 
01468 Tango3DR_Status Tango3DR_extractFloorplanSegment(
01469     const Tango3DR_ReconstructionContext context,
01470     const Tango3DR_GridIndex2D grid_index, Tango3DR_PolygonArray* graphics);
01471 
01486 Tango3DR_Status Tango3DR_extractFullFloorplanImage(
01487     const Tango3DR_ReconstructionContext context, Tango3DR_FloorplanLayer layer,
01488     Tango3DR_Vector2* origin, Tango3DR_ImageBuffer* image);
01489 
01504 Tango3DR_Status Tango3DR_extractFloorplanImageSegment(
01505     const Tango3DR_ReconstructionContext context,
01506     const Tango3DR_GridIndex2D grid_index, Tango3DR_FloorplanLayer layer,
01507     Tango3DR_ImageBuffer* image);
01508 
01512 void Tango3DR_VectorGraphics_destroy(Tango3DR_PolygonArray* graphics);
01513 
01515 
01526 
01533 Tango3DR_Status Tango3DR_AreaDescription_destroy(
01534     Tango3DR_AreaDescription area_description);
01535 
01543 Tango3DR_Status Tango3DR_AreaDescription_saveToAdf(
01544     Tango3DR_AreaDescription area_description, const char* const path);
01545 
01555 Tango3DR_Status Tango3DR_AreaDescription_loadFromAdf(
01556     const char* const path, Tango3DR_AreaDescription* area_description);
01557 
01564 Tango3DR_Status Tango3DR_Trajectory_createFromAreaDescription(
01565     const Tango3DR_AreaDescription area_description,
01566     Tango3DR_Trajectory* trajectory);
01567 
01574 Tango3DR_Status Tango3DR_Trajectory_destroy(Tango3DR_Trajectory trajectory);
01575 
01582 Tango3DR_Status Tango3DR_Trajectory_getEarliestTime(
01583     const Tango3DR_Trajectory trajectory, double* timestamp);
01584 
01591 Tango3DR_Status Tango3DR_Trajectory_getLatestTime(
01592     const Tango3DR_Trajectory trajectory, double* timestamp);
01593 
01603 Tango3DR_Status Tango3DR_getPoseAtTime(const Tango3DR_Trajectory trajectory,
01604                                        const double timestamp,
01605                                        Tango3DR_Pose* tango_pose);
01606 
01608 
01612 
01614 typedef void (*Tango3DR_ProgressCallback)(int progress, void* callback_param);
01615 
01632 Tango3DR_Status Tango3DR_AreaDescription_createFromDataset(
01633     const char* dataset_path, const char* loop_closure_database_path,
01634     Tango3DR_AreaDescription* area_description,
01635     Tango3DR_ProgressCallback progress_callback, void* callback_param);
01636 
01650 Tango3DR_Status Tango3DR_updateFromTrajectoryAndDataset(
01651     const Tango3DR_ReconstructionContext context, const char* dataset_path,
01652     const Tango3DR_Trajectory trajectory,
01653     Tango3DR_ProgressCallback progress_callback, void* callback_param);
01654 
01675 Tango3DR_Status Tango3DR_textureMeshFromDataset(
01676     const Tango3DR_Config texture_config, const char* dataset_path,
01677     const Tango3DR_Trajectory trajectory, const Tango3DR_Mesh* tango_mesh_in,
01678     Tango3DR_Mesh* tango_mesh_out, Tango3DR_ProgressCallback progress_callback,
01679     void* callback_param);
01680 
01681 // TODO(idryanov): Add link to documentation.
01692 Tango3DR_Status Tango3DR_extractRawDataFromDataset(
01693     const char* dataset_path, const char* output_path,
01694     Tango3DR_ProgressCallback progress_callback, void* callback_param);
01695 
01697 
01698 #ifdef __cplusplus
01699 }
01700 #endif
01701 
01702 #endif  // TANGO_3D_RECONSTRUCTION_API_TANGO_3D_RECONSTRUCTION_API_H_


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