Classes | Typedefs | Enumerations | Functions
tango_support.h File Reference

File containing the core functions of Tango Support C API. The Tango Support C API provides helper functions useful to external developers for building Tango applications. More...

#include <tango_client_api/tango_client_api.h>
#include <stdint.h>
Include dependency graph for tango_support.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  TangoSupport_DoubleMatrixTransformData
 Struct to hold transformation double matrix and its metadata. More...
struct  TangoSupport_MatrixTransformData
 Struct to hold transformation float matrix and its metadata. More...
struct  TangoSupport_Plane
 A structure to define a plane (ax + by + cz + d = 0), including the intersection point of the plane with the user selected camera-ray and inlier information for the plane for points near the user selected camera-ray. More...

Typedefs

typedef struct
TangoSupport_DoubleMatrixTransformData 
TangoSupport_DoubleMatrixTransformData
 Struct to hold transformation double matrix and its metadata.
typedef TangoErrorType(* TangoSupport_GetCameraIntrinsicsFn )(TangoCameraId camera_id, TangoCameraIntrinsics *intrinsics)
 Typedef for getCameraIntrinsics function signature; required by the TangoSupport_initialize method.
typedef TangoErrorType(* TangoSupport_GetPoseAtTimeFn )(double timestamp, TangoCoordinateFramePair frame, TangoPoseData *pose)
 Typedef for getPostAtTime function signature; required by the TangoSupport_initialize method.
typedef struct
TangoSupport_MatrixTransformData 
TangoSupport_MatrixTransformData
 Struct to hold transformation float matrix and its metadata.

Enumerations

enum  TangoSupport_EngineType { TANGO_SUPPORT_ENGINE_TANGO, TANGO_SUPPORT_ENGINE_OPENGL, TANGO_SUPPORT_ENGINE_UNITY, TANGO_SUPPORT_ENGINE_UNREAL }
enum  TangoSupport_Rotation {
  TANGO_SUPPORT_ROTATION_IGNORED = -1, TANGO_SUPPORT_ROTATION_0 = 0, TANGO_SUPPORT_ROTATION_90 = 1, TANGO_SUPPORT_ROTATION_180 = 2,
  TANGO_SUPPORT_ROTATION_270 = 3
}

Functions

TangoErrorType TangoSupport_calculateRelativePose (double base_timestamp, TangoCoordinateFrameType base_frame, double target_timestamp, TangoCoordinateFrameType target_frame, TangoPoseData *base_frame_T_target_frame)
 Calculates the relative pose of the target frame at time target_timestamp with respect to the base frame at time base_timestamp.
TangoErrorType TangoSupport_createImageBufferManager (TangoImageFormatType format, int width, int height, TangoSupport_ImageBufferManager **manager)
 Create an object for maintaining a set of image buffers for a specified image format and size.
TangoErrorType TangoSupport_createPointCloudManager (size_t max_points, TangoSupport_PointCloudManager **manager)
 Create an object for maintaining a set of point clouds for a specified size.
TangoErrorType TangoSupport_fitMultiplePlaneModelsNearPoint (const TangoPointCloud *point_cloud, const double point_cloud_translation[3], const double point_cloud_orientation[4], const float color_camera_uv_coordinates[2], TangoSupport_Rotation display_rotation, const double color_camera_translation[3], const double color_camera_orientation[4], TangoSupport_Plane **planes, int *number_of_planes)
 Similar to TangoSupport_fitPlaneModelNearPoint, but after finding a plane at the user selection, points fitting the fit plane are removed from the input points to the RANSAC step and the process is repeated until a fit plane is not found. The output planes are in the base frame of the input translations and rotations. This output frame is usually an application's world frame. Unlike the single plane version, the planes need to be freed by calling TangoSupport_freePlaneList.
TangoErrorType TangoSupport_fitPlaneModelNearPoint (const TangoPointCloud *point_cloud, const double point_cloud_translation[3], const double point_cloud_orientation[4], const float color_camera_uv_coordinates[2], TangoSupport_Rotation display_rotation, const double color_camera_translation[3], const double color_camera_orientation[4], double intersection_point[3], double plane_model[4])
 Fits a plane to a point cloud near a user-specified location. This occurs in two passes. First, all points are projected to the image plane and only points near the user selection are kept. Then a plane is fit to the subset using RANSAC. After the RANSAC fit, all inliers from a larger subset of the original input point cloud are used to refine the plane model. The output is in the base frame of the input translations and rotations. This output frame is usually an application's world frame.
TangoErrorType TangoSupport_freeImageBufferManager (TangoSupport_ImageBufferManager *manager)
 Delete the image buffer manager object.
void TangoSupport_freePlaneList (TangoSupport_Plane **planes)
 Free memory allocated in call to TangoSupport_fitMultiplePlaneModelsNearPoint.
TangoErrorType TangoSupport_freePointCloudManager (TangoSupport_PointCloudManager *manager)
 Delete the point cloud manager object.
TangoSupport_Rotation TangoSupport_getAndroidColorCameraRotation ()
 Returns the depth camera rotation in TangoSupport_Rotation format.
TangoSupport_Rotation TangoSupport_getAndroidDepthCameraRotation ()
 Returns the depth camera rotation in TangoSupport_Rotation format.
TangoErrorType TangoSupport_getCameraIntrinsicsBasedOnDisplayRotation (TangoCameraId camera_id, TangoSupport_Rotation display_rotation, TangoCameraIntrinsics *intrinsics)
 Get the camera intrinsics based on the display rotation. This function will query the camera intrinsics and rotate them according to the display rotation.
TangoErrorType TangoSupport_getDoubleMatrixTransformAtTime (double timestamp, TangoCoordinateFrameType base_frame, TangoCoordinateFrameType target_frame, TangoSupport_EngineType base_engine, TangoSupport_EngineType target_engine, TangoSupport_Rotation display_rotation, TangoSupport_DoubleMatrixTransformData *matrix_transform)
 Calculate the tranformation matrix between specified frames and engine types. The output matrix uses doubles and is in column-major order.
TangoErrorType TangoSupport_getLatestImageBuffer (TangoSupport_ImageBufferManager *manager, TangoImageBuffer **image_buffer)
 Check if updated color image data is available. If so, swap new data to the front buffer and set image_buffer to point to the front buffer. Multiple calls to this function must be made from the same thread.
TangoErrorType TangoSupport_getLatestImageBufferAndNewDataFlag (TangoSupport_ImageBufferManager *manager, TangoImageBuffer **image_buffer, bool *new_data)
 Check if updated color image data is available. If so, swap new data to the front buffer and set image_buffer to point to the front buffer. Multiple calls to this function must be made from the same thread. Set new_data to true when image_buffer points to new data.
TangoErrorType TangoSupport_getLatestPointCloud (TangoSupport_PointCloudManager *manager, TangoPointCloud **latest_point_cloud)
 Check if updated point cloud data is available. If so, swap new data to the front buffer and set latest_point_cloud to point to the front buffer. Multiple calls to this function must be made from the same thread.
TangoErrorType TangoSupport_getLatestPointCloudAndNewDataFlag (TangoSupport_PointCloudManager *manager, TangoPointCloud **latest_point_cloud, bool *new_data)
 Check if updated point cloud data is available. If so, swap new data to the front buffer and set latest_point_cloud to point to the front buffer. Multiple calls to this function must be made from the same thread. Set new_data to true if latest_point_cloud points to new point cloud.
TangoErrorType TangoSupport_getLatestPointCloudWithPose (TangoSupport_PointCloudManager *manager, TangoCoordinateFrameType base_frame, TangoSupport_EngineType base_engine, TangoSupport_EngineType target_engine, TangoSupport_Rotation display_rotation, TangoPointCloud **latest_point_cloud, TangoPoseData *pose)
 Returns the latest point cloud that has a pose. There is no target frame parameter because only FRAME_CAMERA_DEPTH has meaningful semantics for point clouds. Assumes the same base_engine and target_engine will be passed in each time.
TangoErrorType TangoSupport_getMatrixTransformAtTime (double timestamp, TangoCoordinateFrameType base_frame, TangoCoordinateFrameType target_frame, TangoSupport_EngineType base_engine, TangoSupport_EngineType target_engine, TangoSupport_Rotation display_rotation, TangoSupport_MatrixTransformData *matrix_transform)
 Calculate the tranformation matrix between specified frames and engine types. The output matrix uses floats and is in column-major order.
TangoErrorType TangoSupport_getPoseAtTime (double timestamp, TangoCoordinateFrameType base_frame, TangoCoordinateFrameType target_frame, TangoSupport_EngineType base_engine, TangoSupport_EngineType target_engine, TangoSupport_Rotation display_rotation, TangoPoseData *pose)
 Get a pose at a given timestamp from the base to the target frame using the specified target and base engine's coordinate system conventions. The base and target engine must either both be right-handed systems or both be left-handed systems.
TangoErrorType TangoSupport_getTangoVersion (void *jni_env, void *activity, int *version)
 Get the version code of the installed TangoCore package.
TangoErrorType TangoSupport_getVideoOverlayUVBasedOnDisplayRotation (const float uv_coordinates[8], TangoSupport_Rotation display_rotation, float output_uv_coordinates[8])
 Get the video overlay UV coordinates based on the display rotation. Given the UV coordinates belonging to a display rotation that matches the camera rotation, this function will return the UV coordinates for any display rotation.
void TangoSupport_initialize (TangoSupport_GetPoseAtTimeFn getPoseAtTime, TangoSupport_GetCameraIntrinsicsFn getCameraIntrinsics)
 Initialize the support library with function pointers required by the library. NOTE: This function must be called after the Android service has been bound.
bool TangoSupport_isValidRotation (TangoSupport_Rotation rotation, bool allowIgnored)
 Indicates whether a given rotation is valid or not.
TangoErrorType TangoSupport_setImageBufferCopyRegion (TangoSupport_ImageBufferManager *manager, int y_only, uint32_t begin_line, uint32_t end_line)
 Limit copying of the incoming image to a specific range of scan lines.
TangoErrorType TangoSupport_updateImageBuffer (TangoSupport_ImageBufferManager *manager, const TangoImageBuffer *image_buffer)
 Updates the back buffer of the manager with new data from the callback. This should be called from the image callback thread.
TangoErrorType TangoSupport_updatePointCloud (TangoSupport_PointCloudManager *manager, const TangoPointCloud *point_cloud)
 Updates the back buffer of the manager. Can be safely called from the callback thread. Update is skipped if point cloud is empty.

Detailed Description

File containing the core functions of Tango Support C API. The Tango Support C API provides helper functions useful to external developers for building Tango applications.

Definition in file tango_support.h.



tango_support
Author(s):
autogenerated on Thu Jun 6 2019 19:49:51