OniDriverAPI.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 ONIDRIVERAPI_H
00022 #define ONIDRIVERAPI_H
00023 
00024 #include "OniPlatform.h"
00025 #include "OniCTypes.h"
00026 #include "OniCProperties.h"
00027 #include "OniDriverTypes.h"
00028 #include <stdarg.h>
00029 
00030 namespace oni { namespace driver {
00031 
00032 class DeviceBase;
00033 class StreamBase;
00034 
00035 typedef void (ONI_CALLBACK_TYPE* DeviceConnectedCallback)(const OniDeviceInfo*, void* pCookie);
00036 typedef void (ONI_CALLBACK_TYPE* DeviceDisconnectedCallback)(const OniDeviceInfo*, void* pCookie);
00037 typedef void (ONI_CALLBACK_TYPE* DeviceStateChangedCallback)(const OniDeviceInfo* deviceId, int errorState, void* pCookie);
00038 typedef void (ONI_CALLBACK_TYPE* NewFrameCallback)(StreamBase* streamId, OniFrame*, void* pCookie);
00039 typedef void (ONI_CALLBACK_TYPE* PropertyChangedCallback)(void* sender, int propertyId, const void* data, int dataSize, void* pCookie);
00040 
00041 class StreamServices : public OniStreamServices
00042 {
00043 public:
00044         int getDefaultRequiredFrameSize()
00045         {
00046                 return OniStreamServices::getDefaultRequiredFrameSize(streamServices);
00047         }
00048 
00049         OniFrame* acquireFrame()
00050         {
00051                 return OniStreamServices::acquireFrame(streamServices);
00052         }
00053 
00054         void addFrameRef(OniFrame* pFrame)
00055         {
00056                 OniStreamServices::addFrameRef(streamServices, pFrame);
00057         }
00058 
00059         void releaseFrame(OniFrame* pFrame)
00060         {
00061                 OniStreamServices::releaseFrame(streamServices, pFrame);
00062         }
00063 };
00064 
00065 class StreamBase
00066 {
00067 public:
00068         StreamBase() : m_newFrameCallback(NULL), m_propertyChangedCallback(NULL) {}
00069         virtual ~StreamBase() {}
00070 
00071         virtual void setServices(StreamServices* pStreamServices) { m_pServices = pStreamServices; }
00072 
00073         virtual OniStatus setProperty(int /*propertyId*/, const void* /*data*/, int /*dataSize*/) {return ONI_STATUS_NOT_IMPLEMENTED;}
00074         virtual OniStatus getProperty(int /*propertyId*/, void* /*data*/, int* /*pDataSize*/) {return ONI_STATUS_NOT_IMPLEMENTED;}
00075         virtual OniBool isPropertySupported(int /*propertyId*/) {return FALSE;}
00076         virtual OniStatus invoke(int /*commandId*/, void* /*data*/, int /*dataSize*/) {return ONI_STATUS_NOT_IMPLEMENTED;}
00077         virtual OniBool isCommandSupported(int /*commandId*/) {return FALSE;}
00078 
00079         virtual int getRequiredFrameSize() { return getServices().getDefaultRequiredFrameSize(); }
00080 
00081         virtual OniStatus start() = 0;
00082         virtual void stop() = 0;
00083 
00084         virtual void setNewFrameCallback(NewFrameCallback handler, void* pCookie) { m_newFrameCallback = handler; m_newFrameCallbackCookie = pCookie; }
00085         virtual void setPropertyChangedCallback(PropertyChangedCallback handler, void* pCookie) { m_propertyChangedCallback = handler; m_propertyChangedCookie = pCookie; }
00086 
00087         virtual void notifyAllProperties() { return; }
00088 
00089         virtual OniStatus convertDepthToColorCoordinates(StreamBase* /*colorStream*/, int /*depthX*/, int /*depthY*/, OniDepthPixel /*depthZ*/, int* /*pColorX*/, int* /*pColorY*/) { return ONI_STATUS_NOT_SUPPORTED; }
00090 
00091         virtual OniStatus convertC2DCoordinates(int /*depthX*/, int /*depthY*/, OniDepthPixel /*depthZ*/, int* /*pColorX*/, int* /*pColorY*/) { return ONI_STATUS_NOT_SUPPORTED; }
00092 
00093         virtual OniStatus convertD2CCoordinates(int /*depthX*/, int /*depthY*/, OniDepthPixel /*depthZ*/, int* /*pColorX*/, int* /*pColorY*/) { return ONI_STATUS_NOT_SUPPORTED; }
00094 protected:
00095         void raiseNewFrame(OniFrame* pFrame) { (*m_newFrameCallback)(this, pFrame, m_newFrameCallbackCookie); }
00096         void raisePropertyChanged(int propertyId, const void* data, int dataSize) { (*m_propertyChangedCallback)(this, propertyId, data, dataSize, m_propertyChangedCookie); }
00097 
00098         StreamServices& getServices() { return *m_pServices; }
00099 
00100 private:
00101         StreamServices* m_pServices;
00102         NewFrameCallback m_newFrameCallback;
00103         void* m_newFrameCallbackCookie;
00104         PropertyChangedCallback m_propertyChangedCallback;
00105         void* m_propertyChangedCookie;
00106 };
00107 
00108 class DeviceBase
00109 {
00110 public:
00111         DeviceBase() {}
00112         virtual ~DeviceBase() {}
00113 
00114         virtual OniStatus getSensorInfoList(OniSensorInfo** pSensorInfos, int* numSensors) = 0;
00115 
00116         virtual StreamBase* createStream(OniSensorType) = 0;
00117         virtual void destroyStream(StreamBase* pStream) = 0;
00118 
00119         virtual OniStatus setProperty(int /*propertyId*/, const void* /*data*/, int /*dataSize*/) {return ONI_STATUS_NOT_IMPLEMENTED;}
00120         virtual OniStatus getProperty(int /*propertyId*/, void* /*data*/, int* /*pDataSize*/) {return ONI_STATUS_NOT_IMPLEMENTED;}
00121         virtual OniBool isPropertySupported(int /*propertyId*/) {return FALSE;}
00122         virtual OniStatus invoke(int /*commandId*/, void* /*data*/, int /*dataSize*/) {return ONI_STATUS_NOT_IMPLEMENTED;}
00123         virtual OniBool isCommandSupported(int /*commandId*/) {return FALSE;}
00124         virtual OniStatus tryManualTrigger() {return ONI_STATUS_OK;}
00125 
00126         virtual void setPropertyChangedCallback(PropertyChangedCallback handler, void* pCookie) { m_propertyChangedCallback = handler; m_propertyChangedCookie = pCookie; }
00127         virtual void notifyAllProperties() { return; }
00128 
00129         virtual OniBool isImageRegistrationModeSupported(OniImageRegistrationMode mode) { return (mode == ONI_IMAGE_REGISTRATION_OFF); }
00130 
00131 protected:
00132         void raisePropertyChanged(int propertyId, const void* data, int dataSize) { (*m_propertyChangedCallback)(this, propertyId, data, dataSize, m_propertyChangedCookie); }
00133 
00134 private:
00135         PropertyChangedCallback m_propertyChangedCallback;
00136         void* m_propertyChangedCookie;
00137 };
00138 
00139 class DriverServices
00140 {
00141 public:
00142         DriverServices(OniDriverServices* pDriverServices) : m_pDriverServices(pDriverServices) {}
00143 
00144         void errorLoggerAppend(const char* format, ...)
00145         {
00146                 va_list args;
00147                 va_start(args, format);
00148                 m_pDriverServices->errorLoggerAppend(m_pDriverServices->driverServices, format, args);
00149                 va_end(args);
00150         }
00151 
00152         void errorLoggerClear()
00153         {
00154                 m_pDriverServices->errorLoggerClear(m_pDriverServices->driverServices);
00155         }
00156 
00157         void log(int severity, const char* file, int line, const char* mask, const char* message)
00158         {
00159                 m_pDriverServices->log(m_pDriverServices->driverServices, severity, file, line, mask, message);
00160         }
00161 
00162 private:
00163         OniDriverServices* m_pDriverServices;
00164 };
00165 
00166 class DriverBase
00167 {
00168 public:
00169         DriverBase(OniDriverServices* pDriverServices) : m_services(pDriverServices)
00170         {}
00171 
00172         virtual ~DriverBase() {}
00173 
00174         virtual OniStatus initialize(DeviceConnectedCallback connectedCallback, DeviceDisconnectedCallback disconnectedCallback, DeviceStateChangedCallback deviceStateChangedCallback, void* pCookie)
00175         {
00176                 m_deviceConnectedEvent = connectedCallback;
00177                 m_deviceDisconnectedEvent = disconnectedCallback;
00178                 m_deviceStateChangedEvent = deviceStateChangedCallback;
00179                 m_pCookie = pCookie;
00180                 return ONI_STATUS_OK;
00181         }
00182 
00183         virtual DeviceBase* deviceOpen(const char* uri, const char* mode) = 0;
00184         virtual void deviceClose(DeviceBase* pDevice) = 0;
00185 
00186         virtual void shutdown() = 0;
00187 
00188         virtual OniStatus tryDevice(const char* /*uri*/) { return ONI_STATUS_ERROR;}
00189 
00190         virtual void* enableFrameSync(StreamBase** /*pStreams*/, int /*streamCount*/) { return NULL; }
00191         virtual void disableFrameSync(void* /*frameSyncGroup*/) {}
00192 
00193 protected:
00194         void deviceConnected(const OniDeviceInfo* pInfo) { (m_deviceConnectedEvent)(pInfo, m_pCookie); }
00195         void deviceDisconnected(const OniDeviceInfo* pInfo) { (m_deviceDisconnectedEvent)(pInfo, m_pCookie); }
00196         void deviceStateChanged(const OniDeviceInfo* pInfo, int errorState) { (m_deviceStateChangedEvent)(pInfo, errorState, m_pCookie); }
00197 
00198         DriverServices& getServices() { return m_services; }
00199 
00200 private:
00201         DeviceConnectedCallback m_deviceConnectedEvent;
00202         DeviceDisconnectedCallback m_deviceDisconnectedEvent;
00203         DeviceStateChangedCallback m_deviceStateChangedEvent;
00204         void* m_pCookie;
00205 
00206         DriverServices m_services;
00207 };
00208 
00209 }} // oni::driver
00210 
00211 #define ONI_EXPORT_DRIVER(DriverClass)                                                                                                                                                                          \
00212                                                                                                                                                                                                                                                         \
00213 oni::driver::DriverBase* g_pDriver = NULL;                                                                                                                                                                      \
00214                                                                                                                                                                                                                                                         \
00215 /* As Driver */                                                                                                                                                                                                                         \
00216 ONI_C_API_EXPORT void oniDriverCreate(OniDriverServices* driverServices) {                                                                                                      \
00217         g_pDriver = XN_NEW(DriverClass, driverServices);                                                                                                                                                \
00218 }                                                                                                                                                                                                                                                       \
00219 ONI_C_API_EXPORT void oniDriverDestroy()                                                                                                                                                                        \
00220 {                                                                                                                                                                                                                                                       \
00221         g_pDriver->shutdown();                                                                                                                                                                                                  \
00222         XN_DELETE(g_pDriver); g_pDriver = NULL;                                                                                                                                                                 \
00223 }                                                                                                                                                                                                                                                       \
00224 ONI_C_API_EXPORT OniStatus oniDriverInitialize(oni::driver::DeviceConnectedCallback deviceConnectedCallback,                            \
00225                                                                                 oni::driver::DeviceDisconnectedCallback deviceDisconnectedCallback,                                     \
00226                                                                                 oni::driver::DeviceStateChangedCallback deviceStateChangedCallback,                                     \
00227                                                                                 void* pCookie)                                                                                                                                          \
00228 {                                                                                                                                                                                                                                                       \
00229         return g_pDriver->initialize(deviceConnectedCallback, deviceDisconnectedCallback, deviceStateChangedCallback, pCookie); \
00230 }                                                                                                                                                                                                                                                       \
00231                                                                                                                                                                                                                                                         \
00232 ONI_C_API_EXPORT OniStatus oniDriverTryDevice(const char* uri)                                                                                                                          \
00233 {                                                                                                                                                                                                                                                       \
00234         return g_pDriver->tryDevice(uri);                                                                                                                                                                               \
00235 }                                                                                                                                                                                                                                                       \
00236                                                                                                                                                                                                                                                         \
00237 /* As Device */                                                                                                                                                                                                                         \
00238 ONI_C_API_EXPORT oni::driver::DeviceBase* oniDriverDeviceOpen(const char* uri, const char* mode)                                                        \
00239 {                                                                                                                                                                                                                                                       \
00240         return g_pDriver->deviceOpen(uri, mode);                                                                                                                                                                \
00241 }                                                                                                                                                                                                                                                       \
00242 ONI_C_API_EXPORT void oniDriverDeviceClose(oni::driver::DeviceBase* pDevice)                                                                                            \
00243 {                                                                                                                                                                                                                                                       \
00244         g_pDriver->deviceClose(pDevice);                                                                                                                                                                                \
00245 }                                                                                                                                                                                                                                                       \
00246                                                                                                                                                                                                                                                         \
00247 ONI_C_API_EXPORT OniStatus oniDriverDeviceGetSensorInfoList(oni::driver::DeviceBase* pDevice, OniSensorInfo** pSensorInfos,     \
00248                                                                                                                         int* numSensors)                                                                                                \
00249 {                                                                                                                                                                                                                                                       \
00250         return pDevice->getSensorInfoList(pSensorInfos, numSensors);                                                                                                                    \
00251 }                                                                                                                                                                                                                                                       \
00252                                                                                                                                                                                                                                                         \
00253 ONI_C_API_EXPORT oni::driver::StreamBase* oniDriverDeviceCreateStream(oni::driver::DeviceBase* pDevice,                                         \
00254                                                                                                                                                 OniSensorType sensorType)                                                       \
00255 {                                                                                                                                                                                                                                                       \
00256         return pDevice->createStream(sensorType);                                                                                                                                                               \
00257 }                                                                                                                                                                                                                                                       \
00258                                                                                                                                                                                                                                                         \
00259 ONI_C_API_EXPORT void oniDriverDeviceDestroyStream(oni::driver::DeviceBase* pDevice, oni::driver::StreamBase* pStream)          \
00260 {                                                                                                                                                                                                                                                       \
00261         return pDevice->destroyStream(pStream);                                                                                                                                                                 \
00262 }                                                                                                                                                                                                                                                       \
00263                                                                                                                                                                                                                                                         \
00264 ONI_C_API_EXPORT OniStatus oniDriverDeviceSetProperty(oni::driver::DeviceBase* pDevice, int propertyId,                                         \
00265                                                                                                         const void* data, int dataSize)                                                                                 \
00266 {                                                                                                                                                                                                                                                       \
00267         return pDevice->setProperty(propertyId, data, dataSize);                                                                                                                                \
00268 }                                                                                                                                                                                                                                                       \
00269 ONI_C_API_EXPORT OniStatus oniDriverDeviceGetProperty(oni::driver::DeviceBase* pDevice, int propertyId,                                         \
00270                                                                                                         void* data, int* pDataSize)                                                                                             \
00271 {                                                                                                                                                                                                                                                       \
00272         return pDevice->getProperty(propertyId, data, pDataSize);                                                                                                                               \
00273 }                                                                                                                                                                                                                                                       \
00274 ONI_C_API_EXPORT OniBool oniDriverDeviceIsPropertySupported(oni::driver::DeviceBase* pDevice, int propertyId)                           \
00275 {                                                                                                                                                                                                                                                       \
00276         return pDevice->isPropertySupported(propertyId);                                                                                                                                                \
00277 }                                                                                                                                                                                                                                                       \
00278 ONI_C_API_EXPORT void oniDriverDeviceSetPropertyChangedCallback(oni::driver::DeviceBase* pDevice,                                                       \
00279         oni::driver::PropertyChangedCallback handler, void* pCookie)                                                                                                                    \
00280 {                                                                                                                                                                                                                                                       \
00281         pDevice->setPropertyChangedCallback(handler, pCookie);                                                                                                                                  \
00282 }                                                                                                                                                                                                                                                       \
00283 ONI_C_API_EXPORT void oniDriverDeviceNotifyAllProperties(oni::driver::DeviceBase* pDevice)                                                                      \
00284 {                                                                                                                                                                                                                                                       \
00285         pDevice->notifyAllProperties();                                                                                                                                                                                 \
00286 }                                                                                                                                                                                                                                                       \
00287 ONI_C_API_EXPORT OniStatus oniDriverDeviceInvoke(oni::driver::DeviceBase* pDevice, int commandId,                                                       \
00288                                                                                                 void* data, int dataSize)                                                                                                       \
00289 {                                                                                                                                                                                                                                                       \
00290         return pDevice->invoke(commandId, data, dataSize);                                                                                                                                              \
00291 }                                                                                                                                                                                                                                                       \
00292 ONI_C_API_EXPORT OniBool oniDriverDeviceIsCommandSupported(oni::driver::DeviceBase* pDevice, int commandId)                                     \
00293 {                                                                                                                                                                                                                                                       \
00294         return pDevice->isCommandSupported(commandId);                                                                                                                                                  \
00295 }                                                                                                                                                                                                                                                       \
00296 ONI_C_API_EXPORT OniStatus oniDriverDeviceTryManualTrigger(oni::driver::DeviceBase* pDevice)                                                            \
00297 {                                                                                                                                                                                                                                                       \
00298         return pDevice->tryManualTrigger();                                                                                                                                                                             \
00299 }                                                                                                                                                                                                                                                       \
00300 ONI_C_API_EXPORT OniBool oniDriverDeviceIsImageRegistrationModeSupported(oni::driver::DeviceBase* pDevice,                                      \
00301         OniImageRegistrationMode mode)                                                                                                                                                                                  \
00302 {                                                                                                                                                                                                                                                       \
00303         return pDevice->isImageRegistrationModeSupported(mode);                                                                                                                                 \
00304 }                                                                                                                                                                                                                                                       \
00305                                                                                                                                                                                                                                                         \
00306 /* As Stream */                                                                                                                                                                                                                         \
00307 ONI_C_API_EXPORT void oniDriverStreamSetServices(oni::driver::StreamBase* pStream, OniStreamServices* pServices)                        \
00308 {                                                                                                                                                                                                                                                       \
00309         pStream->setServices((oni::driver::StreamServices*)pServices);                                                                                                                  \
00310 }                                                                                                                                                                                                                                                       \
00311                                                                                                                                                                                                                                                         \
00312 ONI_C_API_EXPORT OniStatus oniDriverStreamSetProperty(oni::driver::StreamBase* pStream, int propertyId,                                         \
00313                                                                                                         const void* data, int dataSize)                                                                                 \
00314 {                                                                                                                                                                                                                                                       \
00315         return pStream->setProperty(propertyId, data, dataSize);                                                                                                                                \
00316 }                                                                                                                                                                                                                                                       \
00317 ONI_C_API_EXPORT OniStatus oniDriverStreamGetProperty(oni::driver::StreamBase* pStream, int propertyId, void* data,                     \
00318                                                                                                         int* pDataSize)                                                                                                                 \
00319 {                                                                                                                                                                                                                                                       \
00320         return pStream->getProperty(propertyId, data, pDataSize);                                                                                                                               \
00321 }                                                                                                                                                                                                                                                       \
00322 ONI_C_API_EXPORT OniBool oniDriverStreamIsPropertySupported(oni::driver::StreamBase* pStream, int propertyId)                           \
00323 {                                                                                                                                                                                                                                                       \
00324         return pStream->isPropertySupported(propertyId);                                                                                                                                                \
00325 }                                                                                                                                                                                                                                                       \
00326 ONI_C_API_EXPORT void oniDriverStreamSetPropertyChangedCallback(oni::driver::StreamBase* pStream,                                                       \
00327                                                                                                         oni::driver::PropertyChangedCallback handler, void* pCookie)                    \
00328 {                                                                                                                                                                                                                                                       \
00329         pStream->setPropertyChangedCallback(handler, pCookie);                                                                                                                                  \
00330 }                                                                                                                                                                                                                                                       \
00331 ONI_C_API_EXPORT void oniDriverStreamNotifyAllProperties(oni::driver::StreamBase* pStream)                                                                      \
00332 {                                                                                                                                                                                                                                                       \
00333         pStream->notifyAllProperties();                                                                                                                                                                                 \
00334 }                                                                                                                                                                                                                                                       \
00335 ONI_C_API_EXPORT OniStatus oniDriverStreamInvoke(oni::driver::StreamBase* pStream, int commandId,                                                       \
00336                                                                                                 void* data, int dataSize)                                                                                                       \
00337 {                                                                                                                                                                                                                                                       \
00338         return pStream->invoke(commandId, data, dataSize);                                                                                                                                              \
00339 }                                                                                                                                                                                                                                                       \
00340 ONI_C_API_EXPORT OniBool oniDriverStreamIsCommandSupported(oni::driver::StreamBase* pStream, int commandId)                                     \
00341 {                                                                                                                                                                                                                                                       \
00342         return pStream->isCommandSupported(commandId);                                                                                                                                                  \
00343 }                                                                                                                                                                                                                                                       \
00344                                                                                                                                                                                                                                                         \
00345 ONI_C_API_EXPORT OniStatus oniDriverStreamStart(oni::driver::StreamBase* pStream)                                                                                       \
00346 {                                                                                                                                                                                                                                                       \
00347         return pStream->start();                                                                                                                                                                                                \
00348 }                                                                                                                                                                                                                                                       \
00349 ONI_C_API_EXPORT void oniDriverStreamStop(oni::driver::StreamBase* pStream)                                                                                                     \
00350 {                                                                                                                                                                                                                                                       \
00351         pStream->stop();                                                                                                                                                                                                                \
00352 }                                                                                                                                                                                                                                                       \
00353                                                                                                                                                                                                                                                         \
00354 ONI_C_API_EXPORT int oniDriverStreamGetRequiredFrameSize(oni::driver::StreamBase* pStream)                                                                      \
00355 {                                                                                                                                                                                                                                                       \
00356         return pStream->getRequiredFrameSize();                                                                                                                                                                 \
00357 }                                                                                                                                                                                                                                                       \
00358                                                                                                                                                                                                                                                         \
00359 ONI_C_API_EXPORT void oniDriverStreamSetNewFrameCallback(oni::driver::StreamBase* pStream,                                                                      \
00360                                                                                                                 oni::driver::NewFrameCallback handler, void* pCookie)                           \
00361 {                                                                                                                                                                                                                                                       \
00362         pStream->setNewFrameCallback(handler, pCookie);                                                                                                                                                 \
00363 }                                                                                                                                                                                                                                                       \
00364                                                                                                                                                                                                                                                         \
00365 ONI_C_API_EXPORT OniStatus oniDriverStreamConvertDepthToColorCoordinates(oni::driver::StreamBase* pDepthStream,                         \
00366         oni::driver::StreamBase* pColorStream, int depthX, int depthY, OniDepthPixel depthZ, int* pColorX, int* pColorY)                \
00367 {                                                                                                                                                                                                                                                       \
00368         return pDepthStream->convertDepthToColorCoordinates(pColorStream, depthX, depthY, depthZ, pColorX, pColorY);                    \
00369 }                                                                                                                                                                                                                                                       \
00370                                                                                                                             \
00371 ONI_C_API_EXPORT OniStatus oniDriverStreamConvertC2DCoordinates(oni::driver::StreamBase* pDepthStream,                          \
00372                                         int colorX, int colorY, OniDepthPixel depthZ, int* pDepthX, int* pDepthY)               \
00373 {                                                                                                                                                                                                                                                       \
00374         return pDepthStream->convertC2DCoordinates(colorX, colorY, depthZ, pDepthX, pDepthY);                   \
00375 }                                                                                                                                                                                                                                                       \
00376                                                                                                                                                                                                                                                         \
00377 ONI_C_API_EXPORT OniStatus oniDriverStreamConvertD2CCoordinates(oni::driver::StreamBase* pDepthStream,                          \
00378                                        int colorX, int colorY, OniDepthPixel depthZ, int* pDepthX, int* pDepthY)                \
00379 {                                                                                                                                                                                                                                                       \
00380         return pDepthStream->convertD2CCoordinates(colorX, colorY, depthZ, pDepthX, pDepthY);                   \
00381 }                                                                                                                                                                                                                                                       \
00382                                                                                                                                                                                                                                                         \
00383 ONI_C_API_EXPORT void* oniDriverEnableFrameSync(oni::driver::StreamBase** pStreams, int streamCount)                                            \
00384 {                                                                                                                                                                                                                                                       \
00385         return g_pDriver->enableFrameSync(pStreams, streamCount);                                                                                                                               \
00386 }                                                                                                                                                                                                                                                       \
00387                                                                                                                                                                                                                                                         \
00388 ONI_C_API_EXPORT void oniDriverDisableFrameSync(void* frameSyncGroup)                                                                                                           \
00389 {                                                                                                                                                                                                                                                       \
00390         return g_pDriver->disableFrameSync(frameSyncGroup);                                                                                                                                             \
00391 }                                                                                                                                                                                                                                                       \
00392 
00393 #endif // ONIDRIVERAPI_H


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