OniCTypes.h
Go to the documentation of this file.
00001 /*****************************************************************************
00002 *                                                                            *
00003 *  OpenNI 2.x Alpha                                                          *
00004 *  Copyright (C) 2012 PrimeSense Ltd.                                        *
00005 *                                                                            *
00006 *  This file is part of OpenNI.                                              *
00007 *                                                                            *
00008 *  Licensed under the Apache License, Version 2.0 (the "License");           *
00009 *  you may not use this file except in compliance with the License.          *
00010 *  You may obtain a copy of the License at                                   *
00011 *                                                                            *
00012 *      http://www.apache.org/licenses/LICENSE-2.0                            *
00013 *                                                                            *
00014 *  Unless required by applicable law or agreed to in writing, software       *
00015 *  distributed under the License is distributed on an "AS IS" BASIS,         *
00016 *  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  *
00017 *  See the License for the specific language governing permissions and       *
00018 *  limitations under the License.                                            *
00019 *                                                                            *
00020 *****************************************************************************/
00021 #ifndef ONICTYPES_H
00022 #define ONICTYPES_H
00023 
00024 #include "OniPlatform.h"
00025 #include "OniCEnums.h"
00026 
00028 typedef int OniBool;
00029 
00030 #ifndef TRUE
00031 #define TRUE 1
00032 #endif //TRUE
00033 #ifndef FALSE
00034 #define FALSE 0
00035 #endif //FALSE
00036 
00037 #define ONI_MAX_STR 256
00038 #define ONI_MAX_SENSORS 10
00039 
00040 struct OniCallbackHandleImpl;
00041 typedef struct OniCallbackHandleImpl* OniCallbackHandle;
00042 
00044 typedef struct
00045 {
00047         int major;
00049         int minor;
00051         int maintenance;
00053         int build;
00054 } OniVersion;
00055 
00056 typedef int OniHardwareVersion;
00057 
00059 typedef struct
00060 {
00061         OniPixelFormat pixelFormat;
00062         int resolutionX;
00063         int resolutionY;
00064         int fps;
00065 } OniVideoMode;
00066 
00068 typedef struct
00069 {
00070         OniSensorType sensorType;
00071         int numSupportedVideoModes;
00072         OniVideoMode *pSupportedVideoModes;
00073 } OniSensorInfo;
00074 
00076 typedef struct
00077 {
00078         char uri[ONI_MAX_STR];
00079         char vendor[ONI_MAX_STR];
00080         char name[ONI_MAX_STR];
00081         uint16_t usbVendorId;
00082         uint16_t usbProductId;
00083 } OniDeviceInfo;
00084 
00085 typedef struct OBCameraParams
00086 {
00087     float l_intr_p[4];//[fx,fy,cx,cy]
00088     float r_intr_p[4];//[fx,fy,cx,cy]
00089     float r2l_r[9];//[r00,r01,r02;r10,r11,r12;r20,r21,r22]
00090     float r2l_t[3];//[t1,t2,t3]
00091     float l_k[5];//[k1,k2,p1,p2,k3]
00092     float r_k[5];
00093     //int is_mirror;
00094 }OBCameraParams;
00095 
00096 struct _OniDevice;
00097 typedef struct _OniDevice* OniDeviceHandle;
00098 
00099 struct _OniStream;
00100 typedef struct _OniStream* OniStreamHandle;
00101 
00102 struct _OniRecorder;
00103 typedef struct _OniRecorder* OniRecorderHandle;
00104 
00106 typedef struct
00107 {
00108         int dataSize;
00109         void* data;
00110 
00111         OniSensorType sensorType;
00112         uint64_t timestamp;
00113         int frameIndex;
00114 
00115         int width;
00116         int height;
00117 
00118         OniVideoMode videoMode;
00119         OniBool croppingEnabled;
00120         int cropOriginX;
00121         int cropOriginY;
00122 
00123         int stride;
00124 } OniFrame;
00125 
00126 typedef void (ONI_CALLBACK_TYPE* OniNewFrameCallback)(OniStreamHandle stream, void* pCookie);
00127 typedef void (ONI_CALLBACK_TYPE* OniGeneralCallback)(void* pCookie);
00128 typedef void (ONI_CALLBACK_TYPE* OniDeviceInfoCallback)(const OniDeviceInfo* pInfo, void* pCookie);
00129 typedef void (ONI_CALLBACK_TYPE* OniDeviceStateCallback)(const OniDeviceInfo* pInfo, OniDeviceState deviceState, void* pCookie);
00130 
00131 typedef void* (ONI_CALLBACK_TYPE* OniFrameAllocBufferCallback)(int size, void* pCookie);
00132 typedef void (ONI_CALLBACK_TYPE* OniFrameFreeBufferCallback)(void* data, void* pCookie);
00133 
00134 typedef struct
00135 {
00136         OniDeviceInfoCallback           deviceConnected;
00137         OniDeviceInfoCallback           deviceDisconnected;
00138         OniDeviceStateCallback          deviceStateChanged;
00139 } OniDeviceCallbacks;
00140 
00141 typedef struct
00142 {
00143         int enabled;
00144         int originX;
00145         int originY;
00146         int width;
00147         int height;
00148 } OniCropping;
00149 
00150 // Pixel types
00154 typedef uint16_t OniDepthPixel;
00155 typedef uint16_t OniIRPixel;
00156 
00160 typedef uint16_t OniGrayscale16Pixel;
00161 
00165 typedef uint8_t OniGrayscale8Pixel;
00166 
00167 #pragma pack (push, 1)
00168 
00170 typedef struct
00171 {
00172         /* Red value of this pixel. */
00173         uint8_t r;
00174         /* Green value of this pixel. */
00175         uint8_t g;
00176         /* Blue value of this pixel. */
00177         uint8_t b;
00178 } OniRGB888Pixel;
00179 
00185 typedef struct
00186 {
00188         uint8_t u;
00190         uint8_t y1;
00192         uint8_t v;
00194         uint8_t y2;
00195 } OniYUV422DoublePixel;
00196 
00202 typedef struct
00203 {
00205         uint8_t y1;
00207         uint8_t u;
00209         uint8_t y2;
00211         uint8_t v;
00212 } OniYUYVDoublePixel;
00213 
00214 #pragma pack (pop)
00215 
00216 typedef struct
00217 {
00218         int frameIndex;
00219         OniStreamHandle stream;
00220 } OniSeek;
00221 
00222 #endif // ONICTYPES_H


astra_camera
Author(s): Tim Liu
autogenerated on Wed Jul 10 2019 03:18:54