tango_support.h
Go to the documentation of this file.
1 // Copyright 2017 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 
15 #ifndef TANGO_SUPPORT_TANGO_SUPPORT_H_
16 #define TANGO_SUPPORT_TANGO_SUPPORT_H_
17 
19 
20 #include <stdint.h>
21 
26 
27 #ifdef __cplusplus
28 extern "C" {
29 #endif
30 
34 
42 typedef enum {
45 
48 
51 
54 
58 
70 TangoErrorType TangoSupport_getTangoVersion(void* jni_env, void* activity,
71  int* version);
72 
76  double timestamp, TangoCoordinateFramePair frame, TangoPoseData* pose);
77 
81  TangoCameraId camera_id, TangoCameraIntrinsics* intrinsics);
82 
95  TangoSupport_GetPoseAtTimeFn getPoseAtTime,
96  TangoSupport_GetCameraIntrinsicsFn getCameraIntrinsics);
97 
111  const float uv_coordinates[8], TangoSupport_Rotation display_rotation,
112  float output_uv_coordinates[8]);
113 
126  TangoCameraId camera_id, TangoSupport_Rotation display_rotation,
127  TangoCameraIntrinsics* intrinsics);
128 
132 
136 
142  bool allowIgnored);
143 
145 
149 
159 struct TangoSupport_ImageBufferManager;
160 
171  TangoImageFormatType format, int width, int height,
172  TangoSupport_ImageBufferManager** manager);
173 
180  TangoSupport_ImageBufferManager* manager);
181 
201  TangoSupport_ImageBufferManager* manager, int y_only, uint32_t begin_line,
202  uint32_t end_line);
203 
212  TangoSupport_ImageBufferManager* manager,
213  const TangoImageBuffer* image_buffer);
214 
228  TangoSupport_ImageBufferManager* manager, TangoImageBuffer** image_buffer,
229  bool* new_data);
230 
241  TangoSupport_ImageBufferManager* manager, TangoImageBuffer** image_buffer);
242 
244 
249 
252 typedef enum {
258 
262 
266 
270 
273 
277  double timestamp;
278 
280  float matrix[16];
281 
285 
289  double timestamp;
290 
292  double matrix[16];
293 
297 
316  double base_timestamp, TangoCoordinateFrameType base_frame,
317  double target_timestamp, TangoCoordinateFrameType target_frame,
318  TangoPoseData* base_frame_T_target_frame);
319 
357  double timestamp, TangoCoordinateFrameType base_frame,
358  TangoCoordinateFrameType target_frame, TangoSupport_EngineType base_engine,
359  TangoSupport_EngineType target_engine,
360  TangoSupport_Rotation display_rotation, TangoPoseData* pose);
361 
382  double timestamp, TangoCoordinateFrameType base_frame,
383  TangoCoordinateFrameType target_frame, TangoSupport_EngineType base_engine,
384  TangoSupport_EngineType target_engine,
385  TangoSupport_Rotation display_rotation,
386  TangoSupport_MatrixTransformData* matrix_transform);
387 
408  double timestamp, TangoCoordinateFrameType base_frame,
409  TangoCoordinateFrameType target_frame, TangoSupport_EngineType base_engine,
410  TangoSupport_EngineType target_engine,
411  TangoSupport_Rotation display_rotation,
412  TangoSupport_DoubleMatrixTransformData* matrix_transform);
413 
422 struct TangoSupport_PointCloudManager;
423 
433  size_t max_points, TangoSupport_PointCloudManager** manager);
434 
440  TangoSupport_PointCloudManager* manager);
441 
451  TangoSupport_PointCloudManager* manager,
452  const TangoPointCloud* point_cloud);
453 
464  TangoSupport_PointCloudManager* manager,
465  TangoPointCloud** latest_point_cloud);
466 
486 // rotation.
492 // nullptr on failure. This pose has been transformed in the same way as
493 // getPoseAtTime.
498  TangoSupport_PointCloudManager* manager,
499  TangoCoordinateFrameType base_frame, TangoSupport_EngineType base_engine,
500  TangoSupport_EngineType target_engine,
501  TangoSupport_Rotation display_rotation,
502  TangoPointCloud** latest_point_cloud, TangoPoseData* pose);
503 
517  TangoSupport_PointCloudManager* manager,
518  TangoPointCloud** latest_point_cloud, bool* new_data);
520 
524 
561  const TangoPointCloud* point_cloud, const double point_cloud_translation[3],
562  const double point_cloud_orientation[4],
563  const float color_camera_uv_coordinates[2],
564  TangoSupport_Rotation display_rotation,
565  const double color_camera_translation[3],
566  const double color_camera_orientation[4], double intersection_point[3],
567  double plane_model[4]);
568 
574  double intersection_point[3];
575  double plane_equation[4];
577  double inlier_ratio;
578 };
579 
614  const TangoPointCloud* point_cloud, const double point_cloud_translation[3],
615  const double point_cloud_orientation[4],
616  const float color_camera_uv_coordinates[2],
617  TangoSupport_Rotation display_rotation,
618  const double color_camera_translation[3],
619  const double color_camera_orientation[4], TangoSupport_Plane** planes,
620  int* number_of_planes);
621 
627 
629 #ifdef __cplusplus
630 }
631 #endif
632 
633 #endif // TANGO_SUPPORT_TANGO_SUPPORT_H_
TangoCoordinateFrameType
bool TangoSupport_isValidRotation(TangoSupport_Rotation rotation, bool allowIgnored)
Indicates whether a given rotation is valid or not.
double timestamp
Timestamp of the time that this pose estimate corresponds to.
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...
TangoErrorType TangoSupport_freeImageBufferManager(TangoSupport_ImageBufferManager *manager)
Delete the image buffer manager object.
TangoErrorType TangoSupport_createPointCloudManager(size_t max_points, TangoSupport_PointCloudManager **manager)
Create an object for maintaining a set of point clouds for a specified size.
270 degree rotation.
Definition: tango_support.h:56
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 belongin...
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 ...
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&#39;s world frame.
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.
TangoPoseStatusType
TangoErrorType
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...
double timestamp
Timestamp of the time that this pose estimate corresponds to.
TangoErrorType(* TangoSupport_GetCameraIntrinsicsFn)(TangoCameraId camera_id, TangoCameraIntrinsics *intrinsics)
Typedef for getCameraIntrinsics function signature; required by the TangoSupport_initialize method...
Definition: tango_support.h:80
TangoErrorType(* TangoSupport_GetPoseAtTimeFn)(double timestamp, TangoCoordinateFramePair frame, TangoPoseData *pose)
Typedef for getPostAtTime function signature; required by the TangoSupport_initialize method...
Definition: tango_support.h:75
TangoPoseStatusType status_code
The status of the pose, according to the pose lifecycle.
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 fr...
Struct to hold transformation float matrix and its metadata.
struct TangoSupport_DoubleMatrixTransformData TangoSupport_DoubleMatrixTransformData
Struct to hold transformation double matrix and its metadata.
Not apply any rotation.
Definition: tango_support.h:44
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.
TangoCameraId
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...
TangoSupport_EngineType
TangoSupport_Rotation TangoSupport_getAndroidColorCameraRotation()
Returns the depth camera rotation in TangoSupport_Rotation format.
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 imag...
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 th...
struct TangoSupport_MatrixTransformData TangoSupport_MatrixTransformData
Struct to hold transformation float matrix and its metadata.
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 late...
float matrix[16]
Matrix in column major order.
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 imag...
A structure to define a plane (ax + by + cz + d = 0), including the intersection point of the plane w...
TangoSupport_Rotation TangoSupport_getAndroidDepthCameraRotation()
Returns the depth camera rotation in TangoSupport_Rotation format.
TangoErrorType TangoSupport_getTangoVersion(void *jni_env, void *activity, int *version)
Get the version code of the installed TangoCore package.
void TangoSupport_freePlaneList(TangoSupport_Plane **planes)
Free memory allocated in call to TangoSupport_fitMultiplePlaneModelsNearPoint.
Struct to hold transformation double matrix and its metadata.
void TangoSupport_initialize(TangoSupport_GetPoseAtTimeFn getPoseAtTime, TangoSupport_GetCameraIntrinsicsFn getCameraIntrinsics)
Initialize the support library with function pointers required by the library. NOTE: This function mu...
0 degree rotation (natural orientation)
Definition: tango_support.h:47
180 degree rotation.
Definition: tango_support.h:53
TangoImageFormatType
TangoErrorType TangoSupport_freePointCloudManager(TangoSupport_PointCloudManager *manager)
Delete the point cloud manager object.
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_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 late...
90 degree rotation.
Definition: tango_support.h:50
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 ...
TangoSupport_Rotation
Definition: tango_support.h:42
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 intrinsi...
TangoPoseStatusType status_code
The status of the pose, according to the pose lifecycle.


tango_support
Author(s):
autogenerated on Mon Jun 10 2019 15:37:47